1#![doc = "MAVLink uAvionix dialect."]
2#![doc = ""]
3#![doc = "This file was automatically generated, do not edit."]
4#[cfg(feature = "arbitrary")]
5use arbitrary::Arbitrary;
6#[allow(unused_imports)]
7use bitflags::bitflags;
8use mavlink_core::{bytes::Bytes, bytes_mut::BytesMut, MavlinkVersion, Message, MessageData};
9#[allow(unused_imports)]
10use num_derive::FromPrimitive;
11#[allow(unused_imports)]
12use num_derive::ToPrimitive;
13#[allow(unused_imports)]
14use num_traits::FromPrimitive;
15#[allow(unused_imports)]
16use num_traits::ToPrimitive;
17#[cfg(feature = "serde")]
18use serde::{Deserialize, Serialize};
19#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
20#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21#[cfg_attr(feature = "serde", serde(tag = "type"))]
22#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23#[repr(u32)]
24#[doc = "MAVLINK component type reported in HEARTBEAT message. Flight controllers must report the type of the vehicle on which they are mounted (e.g. MAV_TYPE_OCTOROTOR). All other components must report a value appropriate for their type (e.g. a camera must use MAV_TYPE_CAMERA)."]
25pub enum MavType {
26 #[doc = "Generic micro air vehicle"]
27 MAV_TYPE_GENERIC = 0,
28 #[doc = "Fixed wing aircraft."]
29 MAV_TYPE_FIXED_WING = 1,
30 #[doc = "Quadrotor"]
31 MAV_TYPE_QUADROTOR = 2,
32 #[doc = "Coaxial helicopter"]
33 MAV_TYPE_COAXIAL = 3,
34 #[doc = "Normal helicopter with tail rotor."]
35 MAV_TYPE_HELICOPTER = 4,
36 #[doc = "Ground installation"]
37 MAV_TYPE_ANTENNA_TRACKER = 5,
38 #[doc = "Operator control unit / ground control station"]
39 MAV_TYPE_GCS = 6,
40 #[doc = "Airship, controlled"]
41 MAV_TYPE_AIRSHIP = 7,
42 #[doc = "Free balloon, uncontrolled"]
43 MAV_TYPE_FREE_BALLOON = 8,
44 #[doc = "Rocket"]
45 MAV_TYPE_ROCKET = 9,
46 #[doc = "Ground rover"]
47 MAV_TYPE_GROUND_ROVER = 10,
48 #[doc = "Surface vessel, boat, ship"]
49 MAV_TYPE_SURFACE_BOAT = 11,
50 #[doc = "Submarine"]
51 MAV_TYPE_SUBMARINE = 12,
52 #[doc = "Hexarotor"]
53 MAV_TYPE_HEXAROTOR = 13,
54 #[doc = "Octorotor"]
55 MAV_TYPE_OCTOROTOR = 14,
56 #[doc = "Tricopter"]
57 MAV_TYPE_TRICOPTER = 15,
58 #[doc = "Flapping wing"]
59 MAV_TYPE_FLAPPING_WING = 16,
60 #[doc = "Kite"]
61 MAV_TYPE_KITE = 17,
62 #[doc = "Onboard companion controller"]
63 MAV_TYPE_ONBOARD_CONTROLLER = 18,
64 #[doc = "Two-rotor Tailsitter VTOL that additionally uses control surfaces in vertical operation. Note, value previously named MAV_TYPE_VTOL_DUOROTOR."]
65 MAV_TYPE_VTOL_TAILSITTER_DUOROTOR = 19,
66 #[doc = "Quad-rotor Tailsitter VTOL using a V-shaped quad config in vertical operation. Note: value previously named MAV_TYPE_VTOL_QUADROTOR."]
67 MAV_TYPE_VTOL_TAILSITTER_QUADROTOR = 20,
68 #[doc = "Tiltrotor VTOL. Fuselage and wings stay (nominally) horizontal in all flight phases. It able to tilt (some) rotors to provide thrust in cruise flight."]
69 MAV_TYPE_VTOL_TILTROTOR = 21,
70 #[doc = "VTOL with separate fixed rotors for hover and cruise flight. Fuselage and wings stay (nominally) horizontal in all flight phases."]
71 MAV_TYPE_VTOL_FIXEDROTOR = 22,
72 #[doc = "Tailsitter VTOL. Fuselage and wings orientation changes depending on flight phase: vertical for hover, horizontal for cruise. Use more specific VTOL MAV_TYPE_VTOL_TAILSITTER_DUOROTOR or MAV_TYPE_VTOL_TAILSITTER_QUADROTOR if appropriate."]
73 MAV_TYPE_VTOL_TAILSITTER = 23,
74 #[doc = "Tiltwing VTOL. Fuselage stays horizontal in all flight phases. The whole wing, along with any attached engine, can tilt between vertical and horizontal mode."]
75 MAV_TYPE_VTOL_TILTWING = 24,
76 #[doc = "VTOL reserved 5"]
77 MAV_TYPE_VTOL_RESERVED5 = 25,
78 #[doc = "Gimbal"]
79 MAV_TYPE_GIMBAL = 26,
80 #[doc = "ADSB system"]
81 MAV_TYPE_ADSB = 27,
82 #[doc = "Steerable, nonrigid airfoil"]
83 MAV_TYPE_PARAFOIL = 28,
84 #[doc = "Dodecarotor"]
85 MAV_TYPE_DODECAROTOR = 29,
86 #[doc = "Camera"]
87 MAV_TYPE_CAMERA = 30,
88 #[doc = "Charging station"]
89 MAV_TYPE_CHARGING_STATION = 31,
90 #[doc = "FLARM collision avoidance system"]
91 MAV_TYPE_FLARM = 32,
92 #[doc = "Servo"]
93 MAV_TYPE_SERVO = 33,
94 #[doc = "Open Drone ID. See <https://mavlink.io/en/services/opendroneid.html>."]
95 MAV_TYPE_ODID = 34,
96 #[doc = "Decarotor"]
97 MAV_TYPE_DECAROTOR = 35,
98 #[doc = "Battery"]
99 MAV_TYPE_BATTERY = 36,
100 #[doc = "Parachute"]
101 MAV_TYPE_PARACHUTE = 37,
102 #[doc = "Log"]
103 MAV_TYPE_LOG = 38,
104 #[doc = "OSD"]
105 MAV_TYPE_OSD = 39,
106 #[doc = "IMU"]
107 MAV_TYPE_IMU = 40,
108 #[doc = "GPS"]
109 MAV_TYPE_GPS = 41,
110 #[doc = "Winch"]
111 MAV_TYPE_WINCH = 42,
112 #[doc = "Generic multirotor that does not fit into a specific type or whose type is unknown"]
113 MAV_TYPE_GENERIC_MULTIROTOR = 43,
114 #[doc = "Illuminator. An illuminator is a light source that is used for lighting up dark areas external to the sytstem: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
115 MAV_TYPE_ILLUMINATOR = 44,
116 #[doc = "Orbiter spacecraft. Includes satellites orbiting terrestrial and extra-terrestrial bodies. Follows NASA Spacecraft Classification."]
117 MAV_TYPE_SPACECRAFT_ORBITER = 45,
118}
119impl MavType {
120 pub const DEFAULT: Self = Self::MAV_TYPE_GENERIC;
121}
122impl Default for MavType {
123 fn default() -> Self {
124 Self::DEFAULT
125 }
126}
127#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
128#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
129#[cfg_attr(feature = "serde", serde(tag = "type"))]
130#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
131#[repr(u32)]
132#[doc = "Specifies the conditions under which the MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN command should be accepted."]
133pub enum RebootShutdownConditions {
134 #[doc = "Reboot/Shutdown only if allowed by safety checks, such as being landed."]
135 REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED = 0,
136 #[doc = "Force reboot/shutdown of the autopilot/component regardless of system state."]
137 REBOOT_SHUTDOWN_CONDITIONS_FORCE = 20190226,
138}
139impl RebootShutdownConditions {
140 pub const DEFAULT: Self = Self::REBOOT_SHUTDOWN_CONDITIONS_SAFETY_INTERLOCKED;
141}
142impl Default for RebootShutdownConditions {
143 fn default() -> Self {
144 Self::DEFAULT
145 }
146}
147bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Winch status flags used in WINCH_STATUS"] pub struct MavWinchStatusFlag : u32 { # [doc = "Winch is healthy"] const MAV_WINCH_STATUS_HEALTHY = 1 ; # [doc = "Winch line is fully retracted"] const MAV_WINCH_STATUS_FULLY_RETRACTED = 2 ; # [doc = "Winch motor is moving"] const MAV_WINCH_STATUS_MOVING = 4 ; # [doc = "Winch clutch is engaged allowing motor to move freely."] const MAV_WINCH_STATUS_CLUTCH_ENGAGED = 8 ; # [doc = "Winch is locked by locking mechanism."] const MAV_WINCH_STATUS_LOCKED = 16 ; # [doc = "Winch is gravity dropping payload."] const MAV_WINCH_STATUS_DROPPING = 32 ; # [doc = "Winch is arresting payload descent."] const MAV_WINCH_STATUS_ARRESTING = 64 ; # [doc = "Winch is using torque measurements to sense the ground."] const MAV_WINCH_STATUS_GROUND_SENSE = 128 ; # [doc = "Winch is returning to the fully retracted position."] const MAV_WINCH_STATUS_RETRACTING = 256 ; # [doc = "Winch is redelivering the payload. This is a failover state if the line tension goes above a threshold during RETRACTING."] const MAV_WINCH_STATUS_REDELIVER = 512 ; # [doc = "Winch is abandoning the line and possibly payload. Winch unspools the entire calculated line length. This is a failover state from REDELIVER if the number of attempts exceeds a threshold."] const MAV_WINCH_STATUS_ABANDON_LINE = 1024 ; # [doc = "Winch is engaging the locking mechanism."] const MAV_WINCH_STATUS_LOCKING = 2048 ; # [doc = "Winch is spooling on line."] const MAV_WINCH_STATUS_LOAD_LINE = 4096 ; # [doc = "Winch is loading a payload."] const MAV_WINCH_STATUS_LOAD_PAYLOAD = 8192 ; } }
148impl MavWinchStatusFlag {
149 pub const DEFAULT: Self = Self::MAV_WINCH_STATUS_HEALTHY;
150}
151impl Default for MavWinchStatusFlag {
152 fn default() -> Self {
153 Self::DEFAULT
154 }
155}
156#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
157#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
158#[cfg_attr(feature = "serde", serde(tag = "type"))]
159#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
160#[repr(u32)]
161#[doc = "Video stream encodings"]
162pub enum VideoStreamEncoding {
163 #[doc = "Stream encoding is unknown"]
164 VIDEO_STREAM_ENCODING_UNKNOWN = 0,
165 #[doc = "Stream encoding is H.264"]
166 VIDEO_STREAM_ENCODING_H264 = 1,
167 #[doc = "Stream encoding is H.265"]
168 VIDEO_STREAM_ENCODING_H265 = 2,
169}
170impl VideoStreamEncoding {
171 pub const DEFAULT: Self = Self::VIDEO_STREAM_ENCODING_UNKNOWN;
172}
173impl Default for VideoStreamEncoding {
174 fn default() -> Self {
175 Self::DEFAULT
176 }
177}
178#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
179#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
180#[cfg_attr(feature = "serde", serde(tag = "type"))]
181#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
182#[repr(u32)]
183#[doc = "Actuator output function. Values greater or equal to 1000 are autopilot-specific."]
184pub enum ActuatorOutputFunction {
185 #[doc = "No function (disabled)."]
186 ACTUATOR_OUTPUT_FUNCTION_NONE = 0,
187 #[doc = "Motor 1"]
188 ACTUATOR_OUTPUT_FUNCTION_MOTOR1 = 1,
189 #[doc = "Motor 2"]
190 ACTUATOR_OUTPUT_FUNCTION_MOTOR2 = 2,
191 #[doc = "Motor 3"]
192 ACTUATOR_OUTPUT_FUNCTION_MOTOR3 = 3,
193 #[doc = "Motor 4"]
194 ACTUATOR_OUTPUT_FUNCTION_MOTOR4 = 4,
195 #[doc = "Motor 5"]
196 ACTUATOR_OUTPUT_FUNCTION_MOTOR5 = 5,
197 #[doc = "Motor 6"]
198 ACTUATOR_OUTPUT_FUNCTION_MOTOR6 = 6,
199 #[doc = "Motor 7"]
200 ACTUATOR_OUTPUT_FUNCTION_MOTOR7 = 7,
201 #[doc = "Motor 8"]
202 ACTUATOR_OUTPUT_FUNCTION_MOTOR8 = 8,
203 #[doc = "Motor 9"]
204 ACTUATOR_OUTPUT_FUNCTION_MOTOR9 = 9,
205 #[doc = "Motor 10"]
206 ACTUATOR_OUTPUT_FUNCTION_MOTOR10 = 10,
207 #[doc = "Motor 11"]
208 ACTUATOR_OUTPUT_FUNCTION_MOTOR11 = 11,
209 #[doc = "Motor 12"]
210 ACTUATOR_OUTPUT_FUNCTION_MOTOR12 = 12,
211 #[doc = "Motor 13"]
212 ACTUATOR_OUTPUT_FUNCTION_MOTOR13 = 13,
213 #[doc = "Motor 14"]
214 ACTUATOR_OUTPUT_FUNCTION_MOTOR14 = 14,
215 #[doc = "Motor 15"]
216 ACTUATOR_OUTPUT_FUNCTION_MOTOR15 = 15,
217 #[doc = "Motor 16"]
218 ACTUATOR_OUTPUT_FUNCTION_MOTOR16 = 16,
219 #[doc = "Servo 1"]
220 ACTUATOR_OUTPUT_FUNCTION_SERVO1 = 33,
221 #[doc = "Servo 2"]
222 ACTUATOR_OUTPUT_FUNCTION_SERVO2 = 34,
223 #[doc = "Servo 3"]
224 ACTUATOR_OUTPUT_FUNCTION_SERVO3 = 35,
225 #[doc = "Servo 4"]
226 ACTUATOR_OUTPUT_FUNCTION_SERVO4 = 36,
227 #[doc = "Servo 5"]
228 ACTUATOR_OUTPUT_FUNCTION_SERVO5 = 37,
229 #[doc = "Servo 6"]
230 ACTUATOR_OUTPUT_FUNCTION_SERVO6 = 38,
231 #[doc = "Servo 7"]
232 ACTUATOR_OUTPUT_FUNCTION_SERVO7 = 39,
233 #[doc = "Servo 8"]
234 ACTUATOR_OUTPUT_FUNCTION_SERVO8 = 40,
235 #[doc = "Servo 9"]
236 ACTUATOR_OUTPUT_FUNCTION_SERVO9 = 41,
237 #[doc = "Servo 10"]
238 ACTUATOR_OUTPUT_FUNCTION_SERVO10 = 42,
239 #[doc = "Servo 11"]
240 ACTUATOR_OUTPUT_FUNCTION_SERVO11 = 43,
241 #[doc = "Servo 12"]
242 ACTUATOR_OUTPUT_FUNCTION_SERVO12 = 44,
243 #[doc = "Servo 13"]
244 ACTUATOR_OUTPUT_FUNCTION_SERVO13 = 45,
245 #[doc = "Servo 14"]
246 ACTUATOR_OUTPUT_FUNCTION_SERVO14 = 46,
247 #[doc = "Servo 15"]
248 ACTUATOR_OUTPUT_FUNCTION_SERVO15 = 47,
249 #[doc = "Servo 16"]
250 ACTUATOR_OUTPUT_FUNCTION_SERVO16 = 48,
251}
252impl ActuatorOutputFunction {
253 pub const DEFAULT: Self = Self::ACTUATOR_OUTPUT_FUNCTION_NONE;
254}
255impl Default for ActuatorOutputFunction {
256 fn default() -> Self {
257 Self::DEFAULT
258 }
259}
260#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
261#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
262#[cfg_attr(feature = "serde", serde(tag = "type"))]
263#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
264#[repr(u32)]
265#[doc = "Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data. NaN and INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current yaw or latitude rather than a specific value). See <https://mavlink.io/en/guide/xml_schema.html#MAV_CMD> for information about the structure of the MAV_CMD entries"]
266pub enum MavCmd {
267 #[doc = "Navigate to waypoint. This is intended for use in missions (for guided commands outside of missions use MAV_CMD_DO_REPOSITION)."]
268 MAV_CMD_NAV_WAYPOINT = 16,
269 #[doc = "Loiter around this waypoint an unlimited amount of time"]
270 MAV_CMD_NAV_LOITER_UNLIM = 17,
271 #[doc = "Loiter around this waypoint for X turns"]
272 MAV_CMD_NAV_LOITER_TURNS = 18,
273 #[doc = "Loiter at the specified latitude, longitude and altitude for a certain amount of time. Multicopter vehicles stop at the point (within a vehicle-specific acceptance radius). Forward-only moving vehicles (e.g. fixed-wing) circle the point with the specified radius/direction. If the Heading Required parameter (2) is non-zero forward moving aircraft will only leave the loiter circle once heading towards the next waypoint."]
274 MAV_CMD_NAV_LOITER_TIME = 19,
275 #[doc = "Return to launch location"]
276 MAV_CMD_NAV_RETURN_TO_LAUNCH = 20,
277 #[doc = "Land at location."]
278 MAV_CMD_NAV_LAND = 21,
279 #[doc = "Takeoff from ground / hand. Vehicles that support multiple takeoff modes (e.g. VTOL quadplane) should take off using the currently configured mode."]
280 MAV_CMD_NAV_TAKEOFF = 22,
281 #[doc = "Land at local position (local frame only)"]
282 MAV_CMD_NAV_LAND_LOCAL = 23,
283 #[doc = "Takeoff from local position (local frame only)"]
284 MAV_CMD_NAV_TAKEOFF_LOCAL = 24,
285 #[doc = "Vehicle following, i.e. this waypoint represents the position of a moving vehicle"]
286 MAV_CMD_NAV_FOLLOW = 25,
287 #[doc = "Continue on the current course and climb/descend to specified altitude. When the altitude is reached continue to the next command (i.e., don't proceed to the next command until the desired altitude is reached."]
288 MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT = 30,
289 #[doc = "Begin loiter at the specified Latitude and Longitude. If Lat=Lon=0, then loiter at the current position. Don't consider the navigation command complete (don't leave loiter) until the altitude has been reached. Additionally, if the Heading Required parameter is non-zero the aircraft will not leave the loiter until heading toward the next waypoint."]
290 MAV_CMD_NAV_LOITER_TO_ALT = 31,
291 #[doc = "Begin following a target"]
292 MAV_CMD_DO_FOLLOW = 32,
293 #[doc = "Reposition the MAV after a follow target command has been sent"]
294 MAV_CMD_DO_FOLLOW_REPOSITION = 33,
295 #[doc = "Start orbiting on the circumference of a circle defined by the parameters. Setting values to NaN/INT32_MAX (as appropriate) results in using defaults."]
296 MAV_CMD_DO_ORBIT = 34,
297 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
298 MAV_CMD_NAV_ROI = 80,
299 #[doc = "Control autonomous path planning on the MAV."]
300 MAV_CMD_NAV_PATHPLANNING = 81,
301 #[doc = "Navigate to waypoint using a spline path."]
302 MAV_CMD_NAV_SPLINE_WAYPOINT = 82,
303 #[doc = "Takeoff from ground using VTOL mode, and transition to forward flight with specified heading. The command should be ignored by vehicles that dont support both VTOL and fixed-wing flight (multicopters, boats,etc.)."]
304 MAV_CMD_NAV_VTOL_TAKEOFF = 84,
305 #[doc = "Land using VTOL mode"]
306 MAV_CMD_NAV_VTOL_LAND = 85,
307 #[doc = "hand control over to an external controller"]
308 MAV_CMD_NAV_GUIDED_ENABLE = 92,
309 #[doc = "Delay the next navigation command a number of seconds or until a specified time"]
310 MAV_CMD_NAV_DELAY = 93,
311 #[doc = "Descend and place payload. Vehicle moves to specified location, descends until it detects a hanging payload has reached the ground, and then releases the payload. If ground is not detected before the reaching the maximum descent value (param1), the command will complete without releasing the payload."]
312 MAV_CMD_NAV_PAYLOAD_PLACE = 94,
313 #[doc = "NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration"]
314 MAV_CMD_NAV_LAST = 95,
315 #[doc = "Delay mission state machine."]
316 MAV_CMD_CONDITION_DELAY = 112,
317 #[doc = "Ascend/descend to target altitude at specified rate. Delay mission state machine until desired altitude reached."]
318 MAV_CMD_CONDITION_CHANGE_ALT = 113,
319 #[doc = "Delay mission state machine until within desired distance of next NAV point."]
320 MAV_CMD_CONDITION_DISTANCE = 114,
321 #[doc = "Reach a certain target angle."]
322 MAV_CMD_CONDITION_YAW = 115,
323 #[doc = "NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration"]
324 MAV_CMD_CONDITION_LAST = 159,
325 #[doc = "Set system mode."]
326 MAV_CMD_DO_SET_MODE = 176,
327 #[doc = "Jump to the desired command in the mission list. Repeat this action only the specified number of times"]
328 MAV_CMD_DO_JUMP = 177,
329 #[doc = "Change speed and/or throttle set points. The value persists until it is overridden or there is a mode change"]
330 MAV_CMD_DO_CHANGE_SPEED = 178,
331 #[doc = "Sets the home position to either to the current position or a specified position. The home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this command). Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
332 MAV_CMD_DO_SET_HOME = 179,
333 #[doc = "Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter."]
334 MAV_CMD_DO_SET_PARAMETER = 180,
335 #[doc = "Set a relay to a condition."]
336 MAV_CMD_DO_SET_RELAY = 181,
337 #[doc = "Cycle a relay on and off for a desired number of cycles with a desired period."]
338 MAV_CMD_DO_REPEAT_RELAY = 182,
339 #[doc = "Set a servo to a desired PWM value."]
340 MAV_CMD_DO_SET_SERVO = 183,
341 #[doc = "Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period."]
342 MAV_CMD_DO_REPEAT_SERVO = 184,
343 #[doc = "0.5); the ACK should be either MAV_RESULT_FAILED or MAV_RESULT_UNSUPPORTED."]
344 MAV_CMD_DO_FLIGHTTERMINATION = 185,
345 #[doc = "Change altitude set point."]
346 MAV_CMD_DO_CHANGE_ALTITUDE = 186,
347 #[doc = "Sets actuators (e.g. servos) to a desired value. The actuator numbers are mapped to specific outputs (e.g. on any MAIN or AUX PWM or UAVCAN) using a flight-stack specific mechanism (i.e. a parameter)."]
348 MAV_CMD_DO_SET_ACTUATOR = 187,
349 #[doc = "Mission item to specify the start of a failsafe/landing return-path segment (the end of the segment is the next MAV_CMD_DO_LAND_START item). A vehicle that is using missions for landing (e.g. in a return mode) will join the mission on the closest path of the return-path segment (instead of MAV_CMD_DO_LAND_START or the nearest waypoint). The main use case is to minimize the failsafe flight path in corridor missions, where the inbound/outbound paths are constrained (by geofences) to the same particular path. The MAV_CMD_NAV_RETURN_PATH_START would be placed at the start of the return path. If a failsafe occurs on the outbound path the vehicle will move to the nearest point on the return path (which is parallel for this kind of mission), effectively turning round and following the shortest path to landing. If a failsafe occurs on the inbound path the vehicle is already on the return segment and will continue to landing. The Latitude/Longitude/Altitude are optional, and may be set to 0 if not needed. If specified, the item defines the waypoint at which the return segment starts. If sent using as a command, the vehicle will perform a mission landing (using the land segment if defined) or reject the command if mission landings are not supported, or no mission landing is defined. When used as a command any position information in the command is ignored."]
350 MAV_CMD_DO_RETURN_PATH_START = 188,
351 #[doc = "Mission item to mark the start of a mission landing pattern, or a command to land with a mission landing pattern. When used in a mission, this is a marker for the start of a sequence of mission items that represent a landing pattern. It should be followed by a navigation item that defines the first waypoint of the landing sequence. The start marker positional params are used only for selecting what landing pattern to use if several are defined in the mission (the selected pattern will be the one with the marker position that is closest to the vehicle when a landing is commanded). If the marker item position has zero-values for latitude, longitude, and altitude, then landing pattern selection is instead based on the position of the first waypoint in the landing sequence. \t When sent as a command it triggers a landing using a mission landing pattern. \t The location parameters are not used in this case, and should be set to 0."]
352 MAV_CMD_DO_LAND_START = 189,
353 #[doc = "Mission command to perform a landing from a rally point."]
354 MAV_CMD_DO_RALLY_LAND = 190,
355 #[doc = "Mission command to safely abort an autonomous landing."]
356 MAV_CMD_DO_GO_AROUND = 191,
357 #[doc = "Reposition the vehicle to a specific WGS84 global position. This command is intended for guided commands (for missions use MAV_CMD_NAV_WAYPOINT instead)."]
358 MAV_CMD_DO_REPOSITION = 192,
359 #[doc = "If in a GPS controlled position mode, hold the current position or continue."]
360 MAV_CMD_DO_PAUSE_CONTINUE = 193,
361 #[doc = "Set moving direction to forward or reverse."]
362 MAV_CMD_DO_SET_REVERSE = 194,
363 #[doc = "Sets the region of interest (ROI) to a location. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal is not to react to this message."]
364 MAV_CMD_DO_SET_ROI_LOCATION = 195,
365 #[doc = "Sets the region of interest (ROI) to be toward next waypoint, with optional pitch/roll/yaw offset. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
366 MAV_CMD_DO_SET_ROI_WPNEXT_OFFSET = 196,
367 #[doc = "Cancels any previous ROI command returning the vehicle/sensors to default flight characteristics. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message. After this command the gimbal manager should go back to manual input if available, and otherwise assume a neutral position."]
368 MAV_CMD_DO_SET_ROI_NONE = 197,
369 #[doc = "Mount tracks system with specified system ID. Determination of target vehicle position may be done with GLOBAL_POSITION_INT or any other means. This command can be sent to a gimbal manager but not to a gimbal device. A gimbal device is not to react to this message."]
370 MAV_CMD_DO_SET_ROI_SYSID = 198,
371 #[doc = "Control onboard camera system."]
372 MAV_CMD_DO_CONTROL_VIDEO = 200,
373 #[doc = "Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicle's control system to control the vehicle attitude and the attitude of various sensors such as cameras."]
374 MAV_CMD_DO_SET_ROI = 201,
375 #[doc = "Configure digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
376 MAV_CMD_DO_DIGICAM_CONFIGURE = 202,
377 #[doc = "Control digital camera. This is a fallback message for systems that have not yet implemented PARAM_EXT_XXX messages and camera definition files (see <https://mavlink.io/en/services/camera_def.html> )."]
378 MAV_CMD_DO_DIGICAM_CONTROL = 203,
379 #[doc = "Mission command to configure a camera or antenna mount"]
380 MAV_CMD_DO_MOUNT_CONFIGURE = 204,
381 #[doc = "Mission command to control a camera or antenna mount"]
382 MAV_CMD_DO_MOUNT_CONTROL = 205,
383 #[doc = "Mission command to set camera trigger distance for this flight. The camera is triggered each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera."]
384 MAV_CMD_DO_SET_CAM_TRIGG_DIST = 206,
385 #[doc = "Enable the geofence. This can be used in a mission or via the command protocol. The persistence/lifetime of the setting is undefined. Depending on flight stack implementation it may persist until superseded, or it may revert to a system default at the end of a mission. Flight stacks typically reset the setting to system defaults on reboot."]
386 MAV_CMD_DO_FENCE_ENABLE = 207,
387 #[doc = "Mission item/command to release a parachute or enable/disable auto release."]
388 MAV_CMD_DO_PARACHUTE = 208,
389 #[doc = "Command to perform motor test."]
390 MAV_CMD_DO_MOTOR_TEST = 209,
391 #[doc = "Change to/from inverted flight."]
392 MAV_CMD_DO_INVERTED_FLIGHT = 210,
393 #[doc = "Mission command to operate a gripper."]
394 MAV_CMD_DO_GRIPPER = 211,
395 #[doc = "Enable/disable autotune."]
396 MAV_CMD_DO_AUTOTUNE_ENABLE = 212,
397 #[doc = "Sets a desired vehicle turn angle and speed change."]
398 MAV_CMD_NAV_SET_YAW_SPEED = 213,
399 #[doc = "Mission command to set camera trigger interval for this flight. If triggering is enabled, the camera is triggered each time this interval expires. This command can also be used to set the shutter integration time for the camera."]
400 MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL = 214,
401 #[doc = "Mission command to control a camera or antenna mount, using a quaternion as reference."]
402 MAV_CMD_DO_MOUNT_CONTROL_QUAT = 220,
403 #[doc = "set id of master controller"]
404 MAV_CMD_DO_GUIDED_MASTER = 221,
405 #[doc = "Set limits for external control"]
406 MAV_CMD_DO_GUIDED_LIMITS = 222,
407 #[doc = "Control vehicle engine. This is interpreted by the vehicles engine controller to change the target engine state. It is intended for vehicles with internal combustion engines"]
408 MAV_CMD_DO_ENGINE_CONTROL = 223,
409 #[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. \t Note that mission jump repeat counters are not reset unless param2 is set (see MAV_CMD_DO_JUMP param2). This command may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this command must not trigger a switch to mission mode. The mission may be \"reset\" using param2. Resetting sets jump counters to initial values (to reset counters without changing the current mission item set the param1 to `-1`). Resetting also explicitly changes a mission state of MISSION_STATE_COMPLETE to MISSION_STATE_PAUSED or MISSION_STATE_ACTIVE, potentially allowing it to resume when it is (next) in a mission mode. \t The command will ACK with MAV_RESULT_FAILED if the sequence number is out of range (including if there is no mission item)."]
410 MAV_CMD_DO_SET_MISSION_CURRENT = 224,
411 #[doc = "NOP - This command is only used to mark the upper limit of the DO commands in the enumeration"]
412 MAV_CMD_DO_LAST = 240,
413 #[doc = "Trigger calibration. This command will be only accepted if in pre-flight mode. Except for Temperature Calibration, only one sensor should be set in a single message and all others should be zero."]
414 MAV_CMD_PREFLIGHT_CALIBRATION = 241,
415 #[doc = "Set sensor offsets. This command will be only accepted if in pre-flight mode."]
416 MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS = 242,
417 #[doc = "Trigger UAVCAN configuration (actuator ID assignment and direction mapping). Note that this maps to the legacy UAVCAN v0 function UAVCAN_ENUMERATE, which is intended to be executed just once during initial vehicle configuration (it is not a normal pre-flight command and has been poorly named)."]
418 MAV_CMD_PREFLIGHT_UAVCAN = 243,
419 #[doc = "Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode."]
420 MAV_CMD_PREFLIGHT_STORAGE = 245,
421 #[doc = "Request the reboot or shutdown of system components."]
422 MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN = 246,
423 #[doc = "Override current mission with command to pause mission, pause mission and move to position, continue/resume mission. When param 1 indicates that the mission is paused (MAV_GOTO_DO_HOLD), param 2 defines whether it holds in place or moves to another position."]
424 MAV_CMD_OVERRIDE_GOTO = 252,
425 #[doc = "Mission command to set a Camera Auto Mount Pivoting Oblique Survey (Replaces CAM_TRIGG_DIST for this purpose). The camera is triggered each time this distance is exceeded, then the mount moves to the next position. Params 4~6 set-up the angle limits and number of positions for oblique survey, where mount-enabled vehicles automatically roll the camera between shots to emulate an oblique camera setup (providing an increased HFOV). This command can also be used to set the shutter integration time for the camera."]
426 MAV_CMD_OBLIQUE_SURVEY = 260,
427 #[doc = "Enable the specified standard MAVLink mode. If the specified mode is not supported, the vehicle should ACK with MAV_RESULT_FAILED. See <https://mavlink.io/en/services/standard_modes.html>"]
428 MAV_CMD_DO_SET_STANDARD_MODE = 262,
429 #[doc = "start running a mission"]
430 MAV_CMD_MISSION_START = 300,
431 #[doc = "Actuator testing command. This is similar to MAV_CMD_DO_MOTOR_TEST but operates on the level of output functions, i.e. it is possible to test Motor1 independent from which output it is configured on. Autopilots must NACK this command with MAV_RESULT_TEMPORARILY_REJECTED while armed."]
432 MAV_CMD_ACTUATOR_TEST = 310,
433 #[doc = "Actuator configuration command."]
434 MAV_CMD_CONFIGURE_ACTUATOR = 311,
435 #[doc = "Arms / Disarms a component"]
436 MAV_CMD_COMPONENT_ARM_DISARM = 400,
437 #[doc = "Instructs a target system to run pre-arm checks. This allows preflight checks to be run on demand, which may be useful on systems that normally run them at low rate, or which do not trigger checks when the armable state might have changed. This command should return MAV_RESULT_ACCEPTED if it will run the checks. The results of the checks are usually then reported in SYS_STATUS messages (this is system-specific). The command should return MAV_RESULT_TEMPORARILY_REJECTED if the system is already armed."]
438 MAV_CMD_RUN_PREARM_CHECKS = 401,
439 #[doc = "Turns illuminators ON/OFF. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
440 MAV_CMD_ILLUMINATOR_ON_OFF = 405,
441 #[doc = "Configures illuminator settings. An illuminator is a light source that is used for lighting up dark areas external to the system: e.g. a torch or searchlight (as opposed to a light source for illuminating the system itself, e.g. an indicator light)."]
442 MAV_CMD_DO_ILLUMINATOR_CONFIGURE = 406,
443 #[doc = "Request the home position from the vehicle. \t The vehicle will ACK the command and then emit the HOME_POSITION message."]
444 MAV_CMD_GET_HOME_POSITION = 410,
445 #[doc = "Inject artificial failure for testing purposes. Note that autopilots should implement an additional protection before accepting this command such as a specific param setting."]
446 MAV_CMD_INJECT_FAILURE = 420,
447 #[doc = "Starts receiver pairing."]
448 MAV_CMD_START_RX_PAIR = 500,
449 #[doc = "Request the interval between messages for a particular MAVLink message ID. The receiver should ACK the command and then emit its response in a MESSAGE_INTERVAL message."]
450 MAV_CMD_GET_MESSAGE_INTERVAL = 510,
451 #[doc = "Set the interval between messages for a particular MAVLink message ID. This interface replaces REQUEST_DATA_STREAM."]
452 MAV_CMD_SET_MESSAGE_INTERVAL = 511,
453 #[doc = "Request the target system(s) emit a single instance of a specified message (i.e. a \"one-shot\" version of MAV_CMD_SET_MESSAGE_INTERVAL)."]
454 MAV_CMD_REQUEST_MESSAGE = 512,
455 #[doc = "Request MAVLink protocol version compatibility. All receivers should ACK the command and then emit their capabilities in an PROTOCOL_VERSION message"]
456 MAV_CMD_REQUEST_PROTOCOL_VERSION = 519,
457 #[doc = "Request autopilot capabilities. The receiver should ACK the command and then emit its capabilities in an AUTOPILOT_VERSION message"]
458 MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES = 520,
459 #[doc = "Request camera information (CAMERA_INFORMATION)."]
460 MAV_CMD_REQUEST_CAMERA_INFORMATION = 521,
461 #[doc = "Request camera settings (CAMERA_SETTINGS)."]
462 MAV_CMD_REQUEST_CAMERA_SETTINGS = 522,
463 #[doc = "Request storage information (STORAGE_INFORMATION). Use the command's target_component to target a specific component's storage."]
464 MAV_CMD_REQUEST_STORAGE_INFORMATION = 525,
465 #[doc = "Format a storage medium. Once format is complete, a STORAGE_INFORMATION message is sent. Use the command's target_component to target a specific component's storage."]
466 MAV_CMD_STORAGE_FORMAT = 526,
467 #[doc = "Request camera capture status (CAMERA_CAPTURE_STATUS)"]
468 MAV_CMD_REQUEST_CAMERA_CAPTURE_STATUS = 527,
469 #[doc = "Request flight information (FLIGHT_INFORMATION)"]
470 MAV_CMD_REQUEST_FLIGHT_INFORMATION = 528,
471 #[doc = "Reset all camera settings to Factory Default"]
472 MAV_CMD_RESET_CAMERA_SETTINGS = 529,
473 #[doc = "Set camera running mode. Use NaN for reserved values. GCS will send a MAV_CMD_REQUEST_VIDEO_STREAM_STATUS command after a mode change if the camera supports video streaming."]
474 MAV_CMD_SET_CAMERA_MODE = 530,
475 #[doc = "Set camera zoom. Camera must respond with a CAMERA_SETTINGS message (on success)."]
476 MAV_CMD_SET_CAMERA_ZOOM = 531,
477 #[doc = "Set camera focus. Camera must respond with a CAMERA_SETTINGS message (on success)."]
478 MAV_CMD_SET_CAMERA_FOCUS = 532,
479 #[doc = "Set that a particular storage is the preferred location for saving photos, videos, and/or other media (e.g. to set that an SD card is used for storing videos). There can only be one preferred save location for each particular media type: setting a media usage flag will clear/reset that same flag if set on any other storage. If no flag is set the system should use its default storage. A target system can choose to always use default storage, in which case it should ACK the command with MAV_RESULT_UNSUPPORTED. A target system can choose to not allow a particular storage to be set as preferred storage, in which case it should ACK the command with MAV_RESULT_DENIED."]
480 MAV_CMD_SET_STORAGE_USAGE = 533,
481 #[doc = "Set camera source. Changes the camera's active sources on cameras with multiple image sensors."]
482 MAV_CMD_SET_CAMERA_SOURCE = 534,
483 #[doc = "Tagged jump target. Can be jumped to with MAV_CMD_DO_JUMP_TAG."]
484 MAV_CMD_JUMP_TAG = 600,
485 #[doc = "Jump to the matching tag in the mission list. Repeat this action for the specified number of times. A mission should contain a single matching tag for each jump. If this is not the case then a jump to a missing tag should complete the mission, and a jump where there are multiple matching tags should always select the one with the lowest mission sequence number."]
486 MAV_CMD_DO_JUMP_TAG = 601,
487 #[doc = "Set gimbal manager pitch/yaw setpoints (low rate command). It is possible to set combinations of the values below. E.g. an angle as well as a desired angular rate can be used to get to this angle at a certain angular rate, or an angular rate only will result in continuous turning. NaN is to be used to signal unset. Note: only the gimbal manager will react to this command - it will be ignored by a gimbal device. Use GIMBAL_MANAGER_SET_PITCHYAW if you need to stream pitch/yaw setpoints at higher rate."]
488 MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW = 1000,
489 #[doc = "Gimbal configuration to set which sysid/compid is in primary and secondary control."]
490 MAV_CMD_DO_GIMBAL_MANAGER_CONFIGURE = 1001,
491 #[doc = "Start image capture sequence. CAMERA_IMAGE_CAPTURED must be emitted after each capture. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param 1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
492 MAV_CMD_IMAGE_START_CAPTURE = 2000,
493 #[doc = "Stop image capture sequence. Param1 (id) may be used to specify the target camera: 0: all cameras, 1 to 6: autopilot-connected cameras, 7-255: MAVLink camera component ID. It is needed in order to target specific cameras connected to the autopilot, or specific sensors in a multi-sensor camera (neither of which have a distinct MAVLink component ID). It is also needed to specify the target camera in missions. When used in a mission, an autopilot should execute the MAV_CMD for a specified local camera (param1 = 1-6), or resend it as a command if it is intended for a MAVLink camera (param1 = 7 - 255), setting the command's target_component as the param1 value (and setting param1 in the command to zero). If the param1 is 0 the autopilot should do both. When sent in a command the target MAVLink address is set using target_component. If addressed specifically to an autopilot: param1 should be used in the same way as it is for missions (though command should NACK with MAV_RESULT_DENIED if a specified local camera does not exist). If addressed to a MAVLink camera, param1 can be used to address all cameras (0), or to separately address 1 to 7 individual sensors. Other values should be NACKed with MAV_RESULT_DENIED. If the command is broadcast (target_component is 0) then param 1 should be set to 0 (any other value should be NACKED with MAV_RESULT_DENIED). An autopilot would trigger any local cameras and forward the command to all channels."]
494 MAV_CMD_IMAGE_STOP_CAPTURE = 2001,
495 #[doc = "Re-request a CAMERA_IMAGE_CAPTURED message."]
496 MAV_CMD_REQUEST_CAMERA_IMAGE_CAPTURE = 2002,
497 #[doc = "Enable or disable on-board camera triggering system."]
498 MAV_CMD_DO_TRIGGER_CONTROL = 2003,
499 #[doc = "If the camera supports point visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_POINT is set), this command allows to initiate the tracking."]
500 MAV_CMD_CAMERA_TRACK_POINT = 2004,
501 #[doc = "If the camera supports rectangle visual tracking (CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE is set), this command allows to initiate the tracking."]
502 MAV_CMD_CAMERA_TRACK_RECTANGLE = 2005,
503 #[doc = "Stops ongoing tracking."]
504 MAV_CMD_CAMERA_STOP_TRACKING = 2010,
505 #[doc = "Starts video capture (recording)."]
506 MAV_CMD_VIDEO_START_CAPTURE = 2500,
507 #[doc = "Stop the current video capture (recording)."]
508 MAV_CMD_VIDEO_STOP_CAPTURE = 2501,
509 #[doc = "Start video streaming"]
510 MAV_CMD_VIDEO_START_STREAMING = 2502,
511 #[doc = "Stop the given video stream"]
512 MAV_CMD_VIDEO_STOP_STREAMING = 2503,
513 #[doc = "Request video stream information (VIDEO_STREAM_INFORMATION)"]
514 MAV_CMD_REQUEST_VIDEO_STREAM_INFORMATION = 2504,
515 #[doc = "Request video stream status (VIDEO_STREAM_STATUS)"]
516 MAV_CMD_REQUEST_VIDEO_STREAM_STATUS = 2505,
517 #[doc = "Request to start streaming logging data over MAVLink (see also LOGGING_DATA message)"]
518 MAV_CMD_LOGGING_START = 2510,
519 #[doc = "Request to stop streaming log data over MAVLink"]
520 MAV_CMD_LOGGING_STOP = 2511,
521 MAV_CMD_AIRFRAME_CONFIGURATION = 2520,
522 #[doc = "Request to start/stop transmitting over the high latency telemetry"]
523 MAV_CMD_CONTROL_HIGH_LATENCY = 2600,
524 #[doc = "Create a panorama at the current position"]
525 MAV_CMD_PANORAMA_CREATE = 2800,
526 #[doc = "Request VTOL transition"]
527 MAV_CMD_DO_VTOL_TRANSITION = 3000,
528 #[doc = "Request authorization to arm the vehicle to a external entity, the arm authorizer is responsible to request all data that is needs from the vehicle before authorize or deny the request. \t\tIf approved the COMMAND_ACK message progress field should be set with period of time that this authorization is valid in seconds. \t\tIf the authorization is denied COMMAND_ACK.result_param2 should be set with one of the reasons in ARM_AUTH_DENIED_REASON."]
529 MAV_CMD_ARM_AUTHORIZATION_REQUEST = 3001,
530 #[doc = "This command sets the submode to standard guided when vehicle is in guided mode. The vehicle holds position and altitude and the user can input the desired velocities along all three axes."]
531 MAV_CMD_SET_GUIDED_SUBMODE_STANDARD = 4000,
532 #[doc = "This command sets submode circle when vehicle is in guided mode. Vehicle flies along a circle facing the center of the circle. The user can input the velocity along the circle and change the radius. If no input is given the vehicle will hold position."]
533 MAV_CMD_SET_GUIDED_SUBMODE_CIRCLE = 4001,
534 #[doc = "Delay mission state machine until gate has been reached."]
535 MAV_CMD_CONDITION_GATE = 4501,
536 #[doc = "Fence return point (there can only be one such point in a geofence definition). If rally points are supported they should be used instead."]
537 MAV_CMD_NAV_FENCE_RETURN_POINT = 5000,
538 #[doc = "Fence vertex for an inclusion polygon (the polygon must not be self-intersecting). The vehicle must stay within this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
539 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_INCLUSION = 5001,
540 #[doc = "Fence vertex for an exclusion polygon (the polygon must not be self-intersecting). The vehicle must stay outside this area. Minimum of 3 vertices required. The vertices for a polygon must be sent sequentially, each with param1 set to the total number of vertices in the polygon."]
541 MAV_CMD_NAV_FENCE_POLYGON_VERTEX_EXCLUSION = 5002,
542 #[doc = "Circular fence area. The vehicle must stay inside this area."]
543 MAV_CMD_NAV_FENCE_CIRCLE_INCLUSION = 5003,
544 #[doc = "Circular fence area. The vehicle must stay outside this area."]
545 MAV_CMD_NAV_FENCE_CIRCLE_EXCLUSION = 5004,
546 #[doc = "Rally point. You can have multiple rally points defined."]
547 MAV_CMD_NAV_RALLY_POINT = 5100,
548 #[doc = "Commands the vehicle to respond with a sequence of messages UAVCAN_NODE_INFO, one message per every UAVCAN node that is online. Note that some of the response messages can be lost, which the receiver can detect easily by checking whether every received UAVCAN_NODE_STATUS has a matching message UAVCAN_NODE_INFO received earlier; if not, this command should be sent again in order to request re-transmission of the node information messages."]
549 MAV_CMD_UAVCAN_GET_NODE_INFO = 5200,
550 #[doc = "Change state of safety switch."]
551 MAV_CMD_DO_SET_SAFETY_SWITCH_STATE = 5300,
552 #[doc = "Trigger the start of an ADSB-out IDENT. This should only be used when requested to do so by an Air Traffic Controller in controlled airspace. This starts the IDENT which is then typically held for 18 seconds by the hardware per the Mode A, C, and S transponder spec."]
553 MAV_CMD_DO_ADSB_OUT_IDENT = 10001,
554 #[doc = "Deploy payload on a Lat / Lon / Alt position. This includes the navigation to reach the required release position and velocity."]
555 MAV_CMD_PAYLOAD_PREPARE_DEPLOY = 30001,
556 #[doc = "Control the payload deployment."]
557 MAV_CMD_PAYLOAD_CONTROL_DEPLOY = 30002,
558 #[doc = "Magnetometer calibration based on provided known yaw. This allows for fast calibration using WMM field tables in the vehicle, given only the known yaw of the vehicle. If Latitude and longitude are both zero then use the current vehicle location."]
559 MAV_CMD_FIXED_MAG_CAL_YAW = 42006,
560 #[doc = "Command to operate winch."]
561 MAV_CMD_DO_WINCH = 42600,
562 #[doc = "Provide an external position estimate for use when dead-reckoning. This is meant to be used for occasional position resets that may be provided by a external system such as a remote pilot using landmarks over a video link."]
563 MAV_CMD_EXTERNAL_POSITION_ESTIMATE = 43003,
564 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
565 MAV_CMD_WAYPOINT_USER_1 = 31000,
566 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
567 MAV_CMD_WAYPOINT_USER_2 = 31001,
568 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
569 MAV_CMD_WAYPOINT_USER_3 = 31002,
570 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
571 MAV_CMD_WAYPOINT_USER_4 = 31003,
572 #[doc = "User defined waypoint item. Ground Station will show the Vehicle as flying through this item."]
573 MAV_CMD_WAYPOINT_USER_5 = 31004,
574 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
575 MAV_CMD_SPATIAL_USER_1 = 31005,
576 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
577 MAV_CMD_SPATIAL_USER_2 = 31006,
578 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
579 MAV_CMD_SPATIAL_USER_3 = 31007,
580 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
581 MAV_CMD_SPATIAL_USER_4 = 31008,
582 #[doc = "User defined spatial item. Ground Station will not show the Vehicle as flying through this item. Example: ROI item."]
583 MAV_CMD_SPATIAL_USER_5 = 31009,
584 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
585 MAV_CMD_USER_1 = 31010,
586 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
587 MAV_CMD_USER_2 = 31011,
588 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
589 MAV_CMD_USER_3 = 31012,
590 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
591 MAV_CMD_USER_4 = 31013,
592 #[doc = "User defined command. Ground Station will not show the Vehicle as flying through this item. Example: MAV_CMD_DO_SET_PARAMETER item."]
593 MAV_CMD_USER_5 = 31014,
594 #[doc = "Request forwarding of CAN packets from the given CAN bus to this component. CAN Frames are sent using CAN_FRAME and CANFD_FRAME messages"]
595 MAV_CMD_CAN_FORWARD = 32000,
596}
597impl MavCmd {
598 pub const DEFAULT: Self = Self::MAV_CMD_NAV_WAYPOINT;
599}
600impl Default for MavCmd {
601 fn default() -> Self {
602 Self::DEFAULT
603 }
604}
605bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmask of (optional) autopilot capabilities (64 bit). If a bit is set, the autopilot supports this capability."] pub struct MavProtocolCapability : u64 { # [doc = "Autopilot supports the MISSION_ITEM float message type. Note that MISSION_ITEM is deprecated, and autopilots should use MISSION_INT instead."] const MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT = 1 ; # [doc = "Autopilot supports the new param float message type."] const MAV_PROTOCOL_CAPABILITY_PARAM_FLOAT = 2 ; # [doc = "Autopilot supports MISSION_ITEM_INT scaled integer message type. Note that this flag must always be set if missions are supported, because missions must always use MISSION_ITEM_INT (rather than MISSION_ITEM, which is deprecated)."] const MAV_PROTOCOL_CAPABILITY_MISSION_INT = 4 ; # [doc = "Autopilot supports COMMAND_INT scaled integer message type."] const MAV_PROTOCOL_CAPABILITY_COMMAND_INT = 8 ; # [doc = "Parameter protocol uses byte-wise encoding of parameter values into param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE = 16 ; # [doc = "Autopilot supports the File Transfer Protocol v1: <https://mavlink.io/en/services/ftp.html>."] const MAV_PROTOCOL_CAPABILITY_FTP = 32 ; # [doc = "Autopilot supports commanding attitude offboard."] const MAV_PROTOCOL_CAPABILITY_SET_ATTITUDE_TARGET = 64 ; # [doc = "Autopilot supports commanding position and velocity targets in local NED frame."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_LOCAL_NED = 128 ; # [doc = "Autopilot supports commanding position and velocity targets in global scaled integers."] const MAV_PROTOCOL_CAPABILITY_SET_POSITION_TARGET_GLOBAL_INT = 256 ; # [doc = "Autopilot supports terrain protocol / data handling."] const MAV_PROTOCOL_CAPABILITY_TERRAIN = 512 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED3 = 1024 ; # [doc = "Autopilot supports the MAV_CMD_DO_FLIGHTTERMINATION command (flight termination)."] const MAV_PROTOCOL_CAPABILITY_FLIGHT_TERMINATION = 2048 ; # [doc = "Autopilot supports onboard compass calibration."] const MAV_PROTOCOL_CAPABILITY_COMPASS_CALIBRATION = 4096 ; # [doc = "Autopilot supports MAVLink version 2."] const MAV_PROTOCOL_CAPABILITY_MAVLINK2 = 8192 ; # [doc = "Autopilot supports mission fence protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_FENCE = 16384 ; # [doc = "Autopilot supports mission rally point protocol."] const MAV_PROTOCOL_CAPABILITY_MISSION_RALLY = 32768 ; # [doc = "Reserved for future use."] const MAV_PROTOCOL_CAPABILITY_RESERVED2 = 65536 ; # [doc = "Parameter protocol uses C-cast of parameter values to set the param_value (float) fields: <https://mavlink.io/en/services/parameter.html#parameter-encoding>. Note that either this flag or MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_BYTEWISE should be set if the parameter protocol is supported."] const MAV_PROTOCOL_CAPABILITY_PARAM_ENCODE_C_CAST = 131072 ; # [doc = "This component implements/is a gimbal manager. This means the GIMBAL_MANAGER_INFORMATION, and other messages can be requested."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_IMPLEMENTS_GIMBAL_MANAGER = 262144 ; # [doc = "Component supports locking control to a particular GCS independent of its system (via MAV_CMD_REQUEST_OPERATOR_CONTROL)."] const MAV_PROTOCOL_CAPABILITY_COMPONENT_ACCEPTS_GCS_CONTROL = 524288 ; } }
606impl MavProtocolCapability {
607 pub const DEFAULT: Self = Self::MAV_PROTOCOL_CAPABILITY_MISSION_FLOAT;
608}
609impl Default for MavProtocolCapability {
610 fn default() -> Self {
611 Self::DEFAULT
612 }
613}
614bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIGHRES_IMU message indicate which fields have updated since the last message"] pub struct HighresImuUpdatedFlags : u16 { # [doc = "The value in the xacc field has been updated"] const HIGHRES_IMU_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIGHRES_IMU_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated since"] const HIGHRES_IMU_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIGHRES_IMU_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIGHRES_IMU_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIGHRES_IMU_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIGHRES_IMU_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIGHRES_IMU_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIGHRES_IMU_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIGHRES_IMU_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIGHRES_IMU_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIGHRES_IMU_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIGHRES_IMU_UPDATED_TEMPERATURE = 4096 ; } }
615impl HighresImuUpdatedFlags {
616 pub const DEFAULT: Self = Self::HIGHRES_IMU_UPDATED_XACC;
617}
618impl Default for HighresImuUpdatedFlags {
619 fn default() -> Self {
620 Self::DEFAULT
621 }
622}
623#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
624#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
625#[cfg_attr(feature = "serde", serde(tag = "type"))]
626#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
627#[repr(u32)]
628#[doc = "RC sub-type of types defined in RC_TYPE. Used in MAV_CMD_START_RX_PAIR. Ignored if value does not correspond to the set RC_TYPE."]
629pub enum RcSubType {
630 #[doc = "Spektrum DSM2"]
631 RC_SUB_TYPE_SPEKTRUM_DSM2 = 0,
632 #[doc = "Spektrum DSMX"]
633 RC_SUB_TYPE_SPEKTRUM_DSMX = 1,
634 #[doc = "Spektrum DSMX8"]
635 RC_SUB_TYPE_SPEKTRUM_DSMX8 = 2,
636}
637impl RcSubType {
638 pub const DEFAULT: Self = Self::RC_SUB_TYPE_SPEKTRUM_DSM2;
639}
640impl Default for RcSubType {
641 fn default() -> Self {
642 Self::DEFAULT
643 }
644}
645#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
646#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
647#[cfg_attr(feature = "serde", serde(tag = "type"))]
648#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
649#[repr(u32)]
650#[doc = "Winch actions."]
651pub enum WinchActions {
652 #[doc = "Allow motor to freewheel."]
653 WINCH_RELAXED = 0,
654 #[doc = "Wind or unwind specified length of line, optionally using specified rate."]
655 WINCH_RELATIVE_LENGTH_CONTROL = 1,
656 #[doc = "Wind or unwind line at specified rate."]
657 WINCH_RATE_CONTROL = 2,
658 #[doc = "Perform the locking sequence to relieve motor while in the fully retracted position. Only action and instance command parameters are used, others are ignored."]
659 WINCH_LOCK = 3,
660 #[doc = "Sequence of drop, slow down, touch down, reel up, lock. Only action and instance command parameters are used, others are ignored."]
661 WINCH_DELIVER = 4,
662 #[doc = "Engage motor and hold current position. Only action and instance command parameters are used, others are ignored."]
663 WINCH_HOLD = 5,
664 #[doc = "Return the reel to the fully retracted position. Only action and instance command parameters are used, others are ignored."]
665 WINCH_RETRACT = 6,
666 #[doc = "Load the reel with line. The winch will calculate the total loaded length and stop when the tension exceeds a threshold. Only action and instance command parameters are used, others are ignored."]
667 WINCH_LOAD_LINE = 7,
668 #[doc = "Spool out the entire length of the line. Only action and instance command parameters are used, others are ignored."]
669 WINCH_ABANDON_LINE = 8,
670 #[doc = "Spools out just enough to present the hook to the user to load the payload. Only action and instance command parameters are used, others are ignored"]
671 WINCH_LOAD_PAYLOAD = 9,
672}
673impl WinchActions {
674 pub const DEFAULT: Self = Self::WINCH_RELAXED;
675}
676impl Default for WinchActions {
677 fn default() -> Self {
678 Self::DEFAULT
679 }
680}
681#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
682#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
683#[cfg_attr(feature = "serde", serde(tag = "type"))]
684#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
685#[repr(u32)]
686#[doc = "These flags are used to diagnose the failure state of CELLULAR_STATUS"]
687pub enum CellularNetworkFailedReason {
688 #[doc = "No error"]
689 CELLULAR_NETWORK_FAILED_REASON_NONE = 0,
690 #[doc = "Error state is unknown"]
691 CELLULAR_NETWORK_FAILED_REASON_UNKNOWN = 1,
692 #[doc = "SIM is required for the modem but missing"]
693 CELLULAR_NETWORK_FAILED_REASON_SIM_MISSING = 2,
694 #[doc = "SIM is available, but not usable for connection"]
695 CELLULAR_NETWORK_FAILED_REASON_SIM_ERROR = 3,
696}
697impl CellularNetworkFailedReason {
698 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_FAILED_REASON_NONE;
699}
700impl Default for CellularNetworkFailedReason {
701 fn default() -> Self {
702 Self::DEFAULT
703 }
704}
705#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
706#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
707#[cfg_attr(feature = "serde", serde(tag = "type"))]
708#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
709#[repr(u32)]
710#[doc = "The ROI (region of interest) for the vehicle. This can be be used by the vehicle for camera/vehicle attitude alignment (see MAV_CMD_NAV_ROI)."]
711pub enum MavRoi {
712 #[doc = "No region of interest."]
713 MAV_ROI_NONE = 0,
714 #[doc = "Point toward next waypoint, with optional pitch/roll/yaw offset."]
715 MAV_ROI_WPNEXT = 1,
716 #[doc = "Point toward given waypoint."]
717 MAV_ROI_WPINDEX = 2,
718 #[doc = "Point toward fixed location."]
719 MAV_ROI_LOCATION = 3,
720 #[doc = "Point toward of given id."]
721 MAV_ROI_TARGET = 4,
722}
723impl MavRoi {
724 pub const DEFAULT: Self = Self::MAV_ROI_NONE;
725}
726impl Default for MavRoi {
727 fn default() -> Self {
728 Self::DEFAULT
729 }
730}
731#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
732#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
733#[cfg_attr(feature = "serde", serde(tag = "type"))]
734#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
735#[repr(u32)]
736#[doc = "Fence types to enable or disable when using MAV_CMD_DO_FENCE_ENABLE. Note that at least one of these flags must be set in MAV_CMD_DO_FENCE_ENABLE.param2. If none are set, the flight stack will ignore the field and enable/disable its default set of fences (usually all of them)."]
737pub enum FenceType {
738 #[doc = "Maximum altitude fence"]
739 FENCE_TYPE_ALT_MAX = 1,
740 #[doc = "Circle fence"]
741 FENCE_TYPE_CIRCLE = 2,
742 #[doc = "Polygon fence"]
743 FENCE_TYPE_POLYGON = 4,
744 #[doc = "Minimum altitude fence"]
745 FENCE_TYPE_ALT_MIN = 8,
746}
747impl FenceType {
748 pub const DEFAULT: Self = Self::FENCE_TYPE_ALT_MAX;
749}
750impl Default for FenceType {
751 fn default() -> Self {
752 Self::DEFAULT
753 }
754}
755#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
756#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
757#[cfg_attr(feature = "serde", serde(tag = "type"))]
758#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
759#[repr(u32)]
760#[doc = "Enumeration of the ADSB altimeter types"]
761pub enum AdsbAltitudeType {
762 #[doc = "Altitude reported from a Baro source using QNH reference"]
763 ADSB_ALTITUDE_TYPE_PRESSURE_QNH = 0,
764 #[doc = "Altitude reported from a GNSS source"]
765 ADSB_ALTITUDE_TYPE_GEOMETRIC = 1,
766}
767impl AdsbAltitudeType {
768 pub const DEFAULT: Self = Self::ADSB_ALTITUDE_TYPE_PRESSURE_QNH;
769}
770impl Default for AdsbAltitudeType {
771 fn default() -> Self {
772 Self::DEFAULT
773 }
774}
775#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
776#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
777#[cfg_attr(feature = "serde", serde(tag = "type"))]
778#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
779#[repr(u32)]
780#[doc = "Enumeration of distance sensor types"]
781pub enum MavDistanceSensor {
782 #[doc = "Laser rangefinder, e.g. LightWare SF02/F or PulsedLight units"]
783 MAV_DISTANCE_SENSOR_LASER = 0,
784 #[doc = "Ultrasound rangefinder, e.g. MaxBotix units"]
785 MAV_DISTANCE_SENSOR_ULTRASOUND = 1,
786 #[doc = "Infrared rangefinder, e.g. Sharp units"]
787 MAV_DISTANCE_SENSOR_INFRARED = 2,
788 #[doc = "Radar type, e.g. uLanding units"]
789 MAV_DISTANCE_SENSOR_RADAR = 3,
790 #[doc = "Broken or unknown type, e.g. analog units"]
791 MAV_DISTANCE_SENSOR_UNKNOWN = 4,
792}
793impl MavDistanceSensor {
794 pub const DEFAULT: Self = Self::MAV_DISTANCE_SENSOR_LASER;
795}
796impl Default for MavDistanceSensor {
797 fn default() -> Self {
798 Self::DEFAULT
799 }
800}
801#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
802#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
803#[cfg_attr(feature = "serde", serde(tag = "type"))]
804#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
805#[repr(u32)]
806#[doc = "Enumeration of estimator types"]
807pub enum MavEstimatorType {
808 #[doc = "Unknown type of the estimator."]
809 MAV_ESTIMATOR_TYPE_UNKNOWN = 0,
810 #[doc = "This is a naive estimator without any real covariance feedback."]
811 MAV_ESTIMATOR_TYPE_NAIVE = 1,
812 #[doc = "Computer vision based estimate. Might be up to scale."]
813 MAV_ESTIMATOR_TYPE_VISION = 2,
814 #[doc = "Visual-inertial estimate."]
815 MAV_ESTIMATOR_TYPE_VIO = 3,
816 #[doc = "Plain GPS estimate."]
817 MAV_ESTIMATOR_TYPE_GPS = 4,
818 #[doc = "Estimator integrating GPS and inertial sensing."]
819 MAV_ESTIMATOR_TYPE_GPS_INS = 5,
820 #[doc = "Estimate from external motion capturing system."]
821 MAV_ESTIMATOR_TYPE_MOCAP = 6,
822 #[doc = "Estimator based on lidar sensor input."]
823 MAV_ESTIMATOR_TYPE_LIDAR = 7,
824 #[doc = "Estimator on autopilot."]
825 MAV_ESTIMATOR_TYPE_AUTOPILOT = 8,
826}
827impl MavEstimatorType {
828 pub const DEFAULT: Self = Self::MAV_ESTIMATOR_TYPE_UNKNOWN;
829}
830impl Default for MavEstimatorType {
831 fn default() -> Self {
832 Self::DEFAULT
833 }
834}
835#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
836#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
837#[cfg_attr(feature = "serde", serde(tag = "type"))]
838#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
839#[repr(u32)]
840#[doc = "Speed setpoint types used in MAV_CMD_DO_CHANGE_SPEED"]
841pub enum SpeedType {
842 #[doc = "Airspeed"]
843 SPEED_TYPE_AIRSPEED = 0,
844 #[doc = "Groundspeed"]
845 SPEED_TYPE_GROUNDSPEED = 1,
846 #[doc = "Climb speed"]
847 SPEED_TYPE_CLIMB_SPEED = 2,
848 #[doc = "Descent speed"]
849 SPEED_TYPE_DESCENT_SPEED = 3,
850}
851impl SpeedType {
852 pub const DEFAULT: Self = Self::SPEED_TYPE_AIRSPEED;
853}
854impl Default for SpeedType {
855 fn default() -> Self {
856 Self::DEFAULT
857 }
858}
859#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
860#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
861#[cfg_attr(feature = "serde", serde(tag = "type"))]
862#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
863#[repr(u32)]
864#[doc = "Flags for CURRENT_EVENT_SEQUENCE."]
865pub enum MavEventCurrentSequenceFlags {
866 #[doc = "A sequence reset has happened (e.g. vehicle reboot)."]
867 MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET = 1,
868}
869impl MavEventCurrentSequenceFlags {
870 pub const DEFAULT: Self = Self::MAV_EVENT_CURRENT_SEQUENCE_FLAGS_RESET;
871}
872impl Default for MavEventCurrentSequenceFlags {
873 fn default() -> Self {
874 Self::DEFAULT
875 }
876}
877#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
878#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
879#[cfg_attr(feature = "serde", serde(tag = "type"))]
880#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
881#[repr(u32)]
882pub enum MavOdidSpeedAcc {
883 #[doc = "The speed accuracy is unknown."]
884 MAV_ODID_SPEED_ACC_UNKNOWN = 0,
885 #[doc = "The speed accuracy is smaller than 10 meters per second."]
886 MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND = 1,
887 #[doc = "The speed accuracy is smaller than 3 meters per second."]
888 MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND = 2,
889 #[doc = "The speed accuracy is smaller than 1 meters per second."]
890 MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND = 3,
891 #[doc = "The speed accuracy is smaller than 0.3 meters per second."]
892 MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND = 4,
893}
894impl MavOdidSpeedAcc {
895 pub const DEFAULT: Self = Self::MAV_ODID_SPEED_ACC_UNKNOWN;
896}
897impl Default for MavOdidSpeedAcc {
898 fn default() -> Self {
899 Self::DEFAULT
900 }
901}
902#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
903#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
904#[cfg_attr(feature = "serde", serde(tag = "type"))]
905#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
906#[repr(u32)]
907#[doc = "Standard modes with a well understood meaning across flight stacks and vehicle types. For example, most flight stack have the concept of a \"return\" or \"RTL\" mode that takes a vehicle to safety, even though the precise mechanics of this mode may differ. The modes supported by a flight stack can be queried using AVAILABLE_MODES and set using MAV_CMD_DO_SET_STANDARD_MODE. The current mode is streamed in CURRENT_MODE. See <https://mavlink.io/en/services/standard_modes.html>"]
908pub enum MavStandardMode {
909 #[doc = "Non standard mode. This may be used when reporting the mode if the current flight mode is not a standard mode."]
910 MAV_STANDARD_MODE_NON_STANDARD = 0,
911 #[doc = "Position mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold both position and altitude against wind and external forces. This mode can only be set by vehicles that can hold a fixed position. Multicopter (MC) vehicles actively brake and hold both position and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to multicopter mode (if needed) but otherwise behave in the same way as MC vehicles. Fixed-wing (FW) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
912 MAV_STANDARD_MODE_POSITION_HOLD = 1,
913 #[doc = "Orbit (manual). Position-controlled and stabilized manual mode. The vehicle circles around a fixed setpoint in the horizontal plane at a particular radius, altitude, and direction. Flight stacks may further allow manual control over the setpoint position, radius, direction, speed, and/or altitude of the circle, but this is not mandated. Flight stacks may support the [MAV_CMD_DO_ORBIT](<https://mavlink.io/en/messages/common.html#MAV_CMD_DO_ORBIT>) for changing the orbit parameters. MC and FW vehicles may support this mode. Hybrid MC/FW (\"VTOL\") vehicles may support this mode in MC/FW or both modes; if the mode is not supported by the current configuration the vehicle should transition to the supported configuration. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
914 MAV_STANDARD_MODE_ORBIT = 2,
915 #[doc = "Cruise mode (manual). Position-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their original track against wind and external forces. Fixed-wing (FW) vehicles level orientation and maintain current track and altitude against wind and external forces. Hybrid MC/FW (\"VTOL\") vehicles first transition to FW mode (if needed) but otherwise behave in the same way as MC vehicles. Multicopter (MC) vehicles must not support this mode. Other vehicle types must not support this mode (this may be revisited through the PR process)."]
916 MAV_STANDARD_MODE_CRUISE = 3,
917 #[doc = "Altitude hold (manual). Altitude-controlled and stabilized manual mode. When sticks are released vehicles return to their level-flight orientation and hold their altitude. MC vehicles continue with existing momentum and may move with wind (or other external forces). FW vehicles continue with current heading, but may be moved off-track by wind. Hybrid MC/FW (\"VTOL\") vehicles behave according to their current configuration/mode (FW or MC). Other vehicle types must not support this mode (this may be revisited through the PR process)."]
918 MAV_STANDARD_MODE_ALTITUDE_HOLD = 4,
919 #[doc = "Safe recovery mode (auto). Automatic mode that takes vehicle to a predefined safe location via a safe flight path, and may also automatically land the vehicle. This mode is more commonly referred to as RTL and/or or Smart RTL. The precise return location, flight path, and landing behaviour depend on vehicle configuration and type. For example, the vehicle might return to the home/launch location, a rally point, or the start of a mission landing, it might follow a direct path, mission path, or breadcrumb path, and land using a mission landing pattern or some other kind of descent."]
920 MAV_STANDARD_MODE_SAFE_RECOVERY = 5,
921 #[doc = "Mission mode (automatic). Automatic mode that executes MAVLink missions. Missions are executed from the current waypoint as soon as the mode is enabled."]
922 MAV_STANDARD_MODE_MISSION = 6,
923 #[doc = "Land mode (auto). Automatic mode that lands the vehicle at the current location. The precise landing behaviour depends on vehicle configuration and type."]
924 MAV_STANDARD_MODE_LAND = 7,
925 #[doc = "Takeoff mode (auto). Automatic takeoff mode. The precise takeoff behaviour depends on vehicle configuration and type."]
926 MAV_STANDARD_MODE_TAKEOFF = 8,
927}
928impl MavStandardMode {
929 pub const DEFAULT: Self = Self::MAV_STANDARD_MODE_NON_STANDARD;
930}
931impl Default for MavStandardMode {
932 fn default() -> Self {
933 Self::DEFAULT
934 }
935}
936bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) error flags (bitmap, 0 means no error)"] pub struct GimbalDeviceErrorFlags : u32 { # [doc = "Gimbal device is limited by hardware roll limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT = 1 ; # [doc = "Gimbal device is limited by hardware pitch limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_PITCH_LIMIT = 2 ; # [doc = "Gimbal device is limited by hardware yaw limit."] const GIMBAL_DEVICE_ERROR_FLAGS_AT_YAW_LIMIT = 4 ; # [doc = "There is an error with the gimbal encoders."] const GIMBAL_DEVICE_ERROR_FLAGS_ENCODER_ERROR = 8 ; # [doc = "There is an error with the gimbal power source."] const GIMBAL_DEVICE_ERROR_FLAGS_POWER_ERROR = 16 ; # [doc = "There is an error with the gimbal motors."] const GIMBAL_DEVICE_ERROR_FLAGS_MOTOR_ERROR = 32 ; # [doc = "There is an error with the gimbal's software."] const GIMBAL_DEVICE_ERROR_FLAGS_SOFTWARE_ERROR = 64 ; # [doc = "There is an error with the gimbal's communication."] const GIMBAL_DEVICE_ERROR_FLAGS_COMMS_ERROR = 128 ; # [doc = "Gimbal device is currently calibrating."] const GIMBAL_DEVICE_ERROR_FLAGS_CALIBRATION_RUNNING = 256 ; # [doc = "Gimbal device is not assigned to a gimbal manager."] const GIMBAL_DEVICE_ERROR_FLAGS_NO_MANAGER = 512 ; } }
937impl GimbalDeviceErrorFlags {
938 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_ERROR_FLAGS_AT_ROLL_LIMIT;
939}
940impl Default for GimbalDeviceErrorFlags {
941 fn default() -> Self {
942 Self::DEFAULT
943 }
944}
945#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
946#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
947#[cfg_attr(feature = "serde", serde(tag = "type"))]
948#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
949#[repr(u32)]
950pub enum MavOdidStatus {
951 #[doc = "The status of the (UA) Unmanned Aircraft is undefined."]
952 MAV_ODID_STATUS_UNDECLARED = 0,
953 #[doc = "The UA is on the ground."]
954 MAV_ODID_STATUS_GROUND = 1,
955 #[doc = "The UA is in the air."]
956 MAV_ODID_STATUS_AIRBORNE = 2,
957 #[doc = "The UA is having an emergency."]
958 MAV_ODID_STATUS_EMERGENCY = 3,
959 #[doc = "The remote ID system is failing or unreliable in some way."]
960 MAV_ODID_STATUS_REMOTE_ID_SYSTEM_FAILURE = 4,
961}
962impl MavOdidStatus {
963 pub const DEFAULT: Self = Self::MAV_ODID_STATUS_UNDECLARED;
964}
965impl Default for MavOdidStatus {
966 fn default() -> Self {
967 Self::DEFAULT
968 }
969}
970#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
971#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
972#[cfg_attr(feature = "serde", serde(tag = "type"))]
973#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
974#[repr(u32)]
975#[doc = "Specifies the datatype of a MAVLink parameter."]
976pub enum MavParamType {
977 #[doc = "8-bit unsigned integer"]
978 MAV_PARAM_TYPE_UINT8 = 1,
979 #[doc = "8-bit signed integer"]
980 MAV_PARAM_TYPE_INT8 = 2,
981 #[doc = "16-bit unsigned integer"]
982 MAV_PARAM_TYPE_UINT16 = 3,
983 #[doc = "16-bit signed integer"]
984 MAV_PARAM_TYPE_INT16 = 4,
985 #[doc = "32-bit unsigned integer"]
986 MAV_PARAM_TYPE_UINT32 = 5,
987 #[doc = "32-bit signed integer"]
988 MAV_PARAM_TYPE_INT32 = 6,
989 #[doc = "64-bit unsigned integer"]
990 MAV_PARAM_TYPE_UINT64 = 7,
991 #[doc = "64-bit signed integer"]
992 MAV_PARAM_TYPE_INT64 = 8,
993 #[doc = "32-bit floating-point"]
994 MAV_PARAM_TYPE_REAL32 = 9,
995 #[doc = "64-bit floating-point"]
996 MAV_PARAM_TYPE_REAL64 = 10,
997}
998impl MavParamType {
999 pub const DEFAULT: Self = Self::MAV_PARAM_TYPE_UINT8;
1000}
1001impl Default for MavParamType {
1002 fn default() -> Self {
1003 Self::DEFAULT
1004 }
1005}
1006#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1007#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1008#[cfg_attr(feature = "serde", serde(tag = "type"))]
1009#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1010#[repr(u32)]
1011#[doc = "ADSB classification for the type of vehicle emitting the transponder signal"]
1012pub enum AdsbEmitterType {
1013 ADSB_EMITTER_TYPE_NO_INFO = 0,
1014 ADSB_EMITTER_TYPE_LIGHT = 1,
1015 ADSB_EMITTER_TYPE_SMALL = 2,
1016 ADSB_EMITTER_TYPE_LARGE = 3,
1017 ADSB_EMITTER_TYPE_HIGH_VORTEX_LARGE = 4,
1018 ADSB_EMITTER_TYPE_HEAVY = 5,
1019 ADSB_EMITTER_TYPE_HIGHLY_MANUV = 6,
1020 ADSB_EMITTER_TYPE_ROTOCRAFT = 7,
1021 ADSB_EMITTER_TYPE_UNASSIGNED = 8,
1022 ADSB_EMITTER_TYPE_GLIDER = 9,
1023 ADSB_EMITTER_TYPE_LIGHTER_AIR = 10,
1024 ADSB_EMITTER_TYPE_PARACHUTE = 11,
1025 ADSB_EMITTER_TYPE_ULTRA_LIGHT = 12,
1026 ADSB_EMITTER_TYPE_UNASSIGNED2 = 13,
1027 ADSB_EMITTER_TYPE_UAV = 14,
1028 ADSB_EMITTER_TYPE_SPACE = 15,
1029 ADSB_EMITTER_TYPE_UNASSGINED3 = 16,
1030 ADSB_EMITTER_TYPE_EMERGENCY_SURFACE = 17,
1031 ADSB_EMITTER_TYPE_SERVICE_SURFACE = 18,
1032 ADSB_EMITTER_TYPE_POINT_OBSTACLE = 19,
1033}
1034impl AdsbEmitterType {
1035 pub const DEFAULT: Self = Self::ADSB_EMITTER_TYPE_NO_INFO;
1036}
1037impl Default for AdsbEmitterType {
1038 fn default() -> Self {
1039 Self::DEFAULT
1040 }
1041}
1042#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1043#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1044#[cfg_attr(feature = "serde", serde(tag = "type"))]
1045#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1046#[repr(u32)]
1047pub enum MavOdidAuthType {
1048 #[doc = "No authentication type is specified."]
1049 MAV_ODID_AUTH_TYPE_NONE = 0,
1050 #[doc = "Signature for the UAS (Unmanned Aircraft System) ID."]
1051 MAV_ODID_AUTH_TYPE_UAS_ID_SIGNATURE = 1,
1052 #[doc = "Signature for the Operator ID."]
1053 MAV_ODID_AUTH_TYPE_OPERATOR_ID_SIGNATURE = 2,
1054 #[doc = "Signature for the entire message set."]
1055 MAV_ODID_AUTH_TYPE_MESSAGE_SET_SIGNATURE = 3,
1056 #[doc = "Authentication is provided by Network Remote ID."]
1057 MAV_ODID_AUTH_TYPE_NETWORK_REMOTE_ID = 4,
1058 #[doc = "The exact authentication type is indicated by the first byte of authentication_data and these type values are managed by ICAO."]
1059 MAV_ODID_AUTH_TYPE_SPECIFIC_AUTHENTICATION = 5,
1060}
1061impl MavOdidAuthType {
1062 pub const DEFAULT: Self = Self::MAV_ODID_AUTH_TYPE_NONE;
1063}
1064impl Default for MavOdidAuthType {
1065 fn default() -> Self {
1066 Self::DEFAULT
1067 }
1068}
1069bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in ESTIMATOR_STATUS message"] pub struct EstimatorStatusFlags : u16 { # [doc = "True if the attitude estimate is good"] const ESTIMATOR_ATTITUDE = 1 ; # [doc = "True if the horizontal velocity estimate is good"] const ESTIMATOR_VELOCITY_HORIZ = 2 ; # [doc = "True if the vertical velocity estimate is good"] const ESTIMATOR_VELOCITY_VERT = 4 ; # [doc = "True if the horizontal position (relative) estimate is good"] const ESTIMATOR_POS_HORIZ_REL = 8 ; # [doc = "True if the horizontal position (absolute) estimate is good"] const ESTIMATOR_POS_HORIZ_ABS = 16 ; # [doc = "True if the vertical position (absolute) estimate is good"] const ESTIMATOR_POS_VERT_ABS = 32 ; # [doc = "True if the vertical position (above ground) estimate is good"] const ESTIMATOR_POS_VERT_AGL = 64 ; # [doc = "True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)"] const ESTIMATOR_CONST_POS_MODE = 128 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_REL = 256 ; # [doc = "True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate"] const ESTIMATOR_PRED_POS_HORIZ_ABS = 512 ; # [doc = "True if the EKF has detected a GPS glitch"] const ESTIMATOR_GPS_GLITCH = 1024 ; # [doc = "True if the EKF has detected bad accelerometer data"] const ESTIMATOR_ACCEL_ERROR = 2048 ; } }
1070impl EstimatorStatusFlags {
1071 pub const DEFAULT: Self = Self::ESTIMATOR_ATTITUDE;
1072}
1073impl Default for EstimatorStatusFlags {
1074 fn default() -> Self {
1075 Self::DEFAULT
1076 }
1077}
1078#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1079#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1080#[cfg_attr(feature = "serde", serde(tag = "type"))]
1081#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1082#[repr(u32)]
1083#[doc = "Indicates the ESC connection type."]
1084pub enum EscConnectionType {
1085 #[doc = "Traditional PPM ESC."]
1086 ESC_CONNECTION_TYPE_PPM = 0,
1087 #[doc = "Serial Bus connected ESC."]
1088 ESC_CONNECTION_TYPE_SERIAL = 1,
1089 #[doc = "One Shot PPM ESC."]
1090 ESC_CONNECTION_TYPE_ONESHOT = 2,
1091 #[doc = "I2C ESC."]
1092 ESC_CONNECTION_TYPE_I2C = 3,
1093 #[doc = "CAN-Bus ESC."]
1094 ESC_CONNECTION_TYPE_CAN = 4,
1095 #[doc = "DShot ESC."]
1096 ESC_CONNECTION_TYPE_DSHOT = 5,
1097}
1098impl EscConnectionType {
1099 pub const DEFAULT: Self = Self::ESC_CONNECTION_TYPE_PPM;
1100}
1101impl Default for EscConnectionType {
1102 fn default() -> Self {
1103 Self::DEFAULT
1104 }
1105}
1106#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1107#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1108#[cfg_attr(feature = "serde", serde(tag = "type"))]
1109#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1110#[repr(u32)]
1111#[doc = "Zoom types for MAV_CMD_SET_CAMERA_ZOOM"]
1112pub enum CameraZoomType {
1113 #[doc = "Zoom one step increment (-1 for wide, 1 for tele)"]
1114 ZOOM_TYPE_STEP = 0,
1115 #[doc = "Continuous normalized zoom in/out rate until stopped. Range -1..1, negative: wide, positive: narrow/tele, 0 to stop zooming. Other values should be clipped to the range."]
1116 ZOOM_TYPE_CONTINUOUS = 1,
1117 #[doc = "Zoom value as proportion of full camera range (a percentage value between 0.0 and 100.0)"]
1118 ZOOM_TYPE_RANGE = 2,
1119 #[doc = "Zoom value/variable focal length in millimetres. Note that there is no message to get the valid zoom range of the camera, so this can type can only be used for cameras where the zoom range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)"]
1120 ZOOM_TYPE_FOCAL_LENGTH = 3,
1121 #[doc = "Zoom value as horizontal field of view in degrees."]
1122 ZOOM_TYPE_HORIZONTAL_FOV = 4,
1123}
1124impl CameraZoomType {
1125 pub const DEFAULT: Self = Self::ZOOM_TYPE_STEP;
1126}
1127impl Default for CameraZoomType {
1128 fn default() -> Self {
1129 Self::DEFAULT
1130 }
1131}
1132#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1133#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1134#[cfg_attr(feature = "serde", serde(tag = "type"))]
1135#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1136#[repr(u32)]
1137#[doc = "Tune formats (used for vehicle buzzer/tone generation)."]
1138pub enum TuneFormat {
1139 #[doc = "Format is QBasic 1.1 Play: <https://www.qbasic.net/en/reference/qb11/Statement/PLAY-006.htm>."]
1140 TUNE_FORMAT_QBASIC1_1 = 1,
1141 #[doc = "Format is Modern Music Markup Language (MML): <https://en.wikipedia.org/wiki/Music_Macro_Language#Modern_MML>."]
1142 TUNE_FORMAT_MML_MODERN = 2,
1143}
1144impl TuneFormat {
1145 pub const DEFAULT: Self = Self::TUNE_FORMAT_QBASIC1_1;
1146}
1147impl Default for TuneFormat {
1148 fn default() -> Self {
1149 Self::DEFAULT
1150 }
1151}
1152#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1153#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1154#[cfg_attr(feature = "serde", serde(tag = "type"))]
1155#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1156#[repr(u32)]
1157pub enum MavOdidCategoryEu {
1158 #[doc = "The category for the UA, according to the EU specification, is undeclared."]
1159 MAV_ODID_CATEGORY_EU_UNDECLARED = 0,
1160 #[doc = "The category for the UA, according to the EU specification, is the Open category."]
1161 MAV_ODID_CATEGORY_EU_OPEN = 1,
1162 #[doc = "The category for the UA, according to the EU specification, is the Specific category."]
1163 MAV_ODID_CATEGORY_EU_SPECIFIC = 2,
1164 #[doc = "The category for the UA, according to the EU specification, is the Certified category."]
1165 MAV_ODID_CATEGORY_EU_CERTIFIED = 3,
1166}
1167impl MavOdidCategoryEu {
1168 pub const DEFAULT: Self = Self::MAV_ODID_CATEGORY_EU_UNDECLARED;
1169}
1170impl Default for MavOdidCategoryEu {
1171 fn default() -> Self {
1172 Self::DEFAULT
1173 }
1174}
1175bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report status/failure cases for a power generator (used in GENERATOR_STATUS). Note that FAULTS are conditions that cause the generator to fail. Warnings are conditions that require attention before the next use (they indicate the system is not operating properly)."] pub struct MavGeneratorStatusFlag : u64 { # [doc = "Generator is off."] const MAV_GENERATOR_STATUS_FLAG_OFF = 1 ; # [doc = "Generator is ready to start generating power."] const MAV_GENERATOR_STATUS_FLAG_READY = 2 ; # [doc = "Generator is generating power."] const MAV_GENERATOR_STATUS_FLAG_GENERATING = 4 ; # [doc = "Generator is charging the batteries (generating enough power to charge and provide the load)."] const MAV_GENERATOR_STATUS_FLAG_CHARGING = 8 ; # [doc = "Generator is operating at a reduced maximum power."] const MAV_GENERATOR_STATUS_FLAG_REDUCED_POWER = 16 ; # [doc = "Generator is providing the maximum output."] const MAV_GENERATOR_STATUS_FLAG_MAXPOWER = 32 ; # [doc = "Generator is near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_WARNING = 64 ; # [doc = "Generator hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_OVERTEMP_FAULT = 128 ; # [doc = "Power electronics are near the maximum operating temperature, cooling is insufficient."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_WARNING = 256 ; # [doc = "Power electronics hit the maximum operating temperature and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_OVERTEMP_FAULT = 512 ; # [doc = "Power electronics experienced a fault and shutdown."] const MAV_GENERATOR_STATUS_FLAG_ELECTRONICS_FAULT = 1024 ; # [doc = "The power source supplying the generator failed e.g. mechanical generator stopped, tether is no longer providing power, solar cell is in shade, hydrogen reaction no longer happening."] const MAV_GENERATOR_STATUS_FLAG_POWERSOURCE_FAULT = 2048 ; # [doc = "Generator controller having communication problems."] const MAV_GENERATOR_STATUS_FLAG_COMMUNICATION_WARNING = 4096 ; # [doc = "Power electronic or generator cooling system error."] const MAV_GENERATOR_STATUS_FLAG_COOLING_WARNING = 8192 ; # [doc = "Generator controller power rail experienced a fault."] const MAV_GENERATOR_STATUS_FLAG_POWER_RAIL_FAULT = 16384 ; # [doc = "Generator controller exceeded the overcurrent threshold and shutdown to prevent damage."] const MAV_GENERATOR_STATUS_FLAG_OVERCURRENT_FAULT = 32768 ; # [doc = "Generator controller detected a high current going into the batteries and shutdown to prevent battery damage."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_OVERCHARGE_CURRENT_FAULT = 65536 ; # [doc = "Generator controller exceeded it's overvoltage threshold and shutdown to prevent it exceeding the voltage rating."] const MAV_GENERATOR_STATUS_FLAG_OVERVOLTAGE_FAULT = 131072 ; # [doc = "Batteries are under voltage (generator will not start)."] const MAV_GENERATOR_STATUS_FLAG_BATTERY_UNDERVOLT_FAULT = 262144 ; # [doc = "Generator start is inhibited by e.g. a safety switch."] const MAV_GENERATOR_STATUS_FLAG_START_INHIBITED = 524288 ; # [doc = "Generator requires maintenance."] const MAV_GENERATOR_STATUS_FLAG_MAINTENANCE_REQUIRED = 1048576 ; # [doc = "Generator is not ready to generate yet."] const MAV_GENERATOR_STATUS_FLAG_WARMING_UP = 2097152 ; # [doc = "Generator is idle."] const MAV_GENERATOR_STATUS_FLAG_IDLE = 4194304 ; } }
1176impl MavGeneratorStatusFlag {
1177 pub const DEFAULT: Self = Self::MAV_GENERATOR_STATUS_FLAG_OFF;
1178}
1179impl Default for MavGeneratorStatusFlag {
1180 fn default() -> Self {
1181 Self::DEFAULT
1182 }
1183}
1184#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1185#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1186#[cfg_attr(feature = "serde", serde(tag = "type"))]
1187#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1188#[repr(u32)]
1189#[doc = "Definitions for aircraft size"]
1190pub enum UavionixAdsbOutCfgAircraftSize {
1191 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA = 0,
1192 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L15M_W23M = 1,
1193 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25M_W28P5M = 2,
1194 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L25_34M = 3,
1195 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_33M = 4,
1196 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L35_38M = 5,
1197 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_39P5M = 6,
1198 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L45_45M = 7,
1199 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_45M = 8,
1200 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L55_52M = 9,
1201 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_59P5M = 10,
1202 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L65_67M = 11,
1203 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W72P5M = 12,
1204 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L75_W80M = 13,
1205 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W80M = 14,
1206 UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_L85_W90M = 15,
1207}
1208impl UavionixAdsbOutCfgAircraftSize {
1209 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CFG_AIRCRAFT_SIZE_NO_DATA;
1210}
1211impl Default for UavionixAdsbOutCfgAircraftSize {
1212 fn default() -> Self {
1213 Self::DEFAULT
1214 }
1215}
1216#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1217#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1218#[cfg_attr(feature = "serde", serde(tag = "type"))]
1219#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1220#[repr(u32)]
1221#[doc = "WiFi Mode."]
1222pub enum WifiConfigApMode {
1223 #[doc = "WiFi mode is undefined."]
1224 WIFI_CONFIG_AP_MODE_UNDEFINED = 0,
1225 #[doc = "WiFi configured as an access point."]
1226 WIFI_CONFIG_AP_MODE_AP = 1,
1227 #[doc = "WiFi configured as a station connected to an existing local WiFi network."]
1228 WIFI_CONFIG_AP_MODE_STATION = 2,
1229 #[doc = "WiFi disabled."]
1230 WIFI_CONFIG_AP_MODE_DISABLED = 3,
1231}
1232impl WifiConfigApMode {
1233 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_MODE_UNDEFINED;
1234}
1235impl Default for WifiConfigApMode {
1236 fn default() -> Self {
1237 Self::DEFAULT
1238 }
1239}
1240#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1241#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1242#[cfg_attr(feature = "serde", serde(tag = "type"))]
1243#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1244#[repr(u32)]
1245#[doc = "Enumeration of VTOL states"]
1246pub enum MavVtolState {
1247 #[doc = "MAV is not configured as VTOL"]
1248 MAV_VTOL_STATE_UNDEFINED = 0,
1249 #[doc = "VTOL is in transition from multicopter to fixed-wing"]
1250 MAV_VTOL_STATE_TRANSITION_TO_FW = 1,
1251 #[doc = "VTOL is in transition from fixed-wing to multicopter"]
1252 MAV_VTOL_STATE_TRANSITION_TO_MC = 2,
1253 #[doc = "VTOL is in multicopter state"]
1254 MAV_VTOL_STATE_MC = 3,
1255 #[doc = "VTOL is in fixed-wing state"]
1256 MAV_VTOL_STATE_FW = 4,
1257}
1258impl MavVtolState {
1259 pub const DEFAULT: Self = Self::MAV_VTOL_STATE_UNDEFINED;
1260}
1261impl Default for MavVtolState {
1262 fn default() -> Self {
1263 Self::DEFAULT
1264 }
1265}
1266#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1267#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1268#[cfg_attr(feature = "serde", serde(tag = "type"))]
1269#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1270#[repr(u32)]
1271#[doc = "Type of landing target"]
1272pub enum LandingTargetType {
1273 #[doc = "Landing target signaled by light beacon (ex: IR-LOCK)"]
1274 LANDING_TARGET_TYPE_LIGHT_BEACON = 0,
1275 #[doc = "Landing target signaled by radio beacon (ex: ILS, NDB)"]
1276 LANDING_TARGET_TYPE_RADIO_BEACON = 1,
1277 #[doc = "Landing target represented by a fiducial marker (ex: ARTag)"]
1278 LANDING_TARGET_TYPE_VISION_FIDUCIAL = 2,
1279 #[doc = "Landing target represented by a pre-defined visual shape/feature (ex: X-marker, H-marker, square)"]
1280 LANDING_TARGET_TYPE_VISION_OTHER = 3,
1281}
1282impl LandingTargetType {
1283 pub const DEFAULT: Self = Self::LANDING_TARGET_TYPE_LIGHT_BEACON;
1284}
1285impl Default for LandingTargetType {
1286 fn default() -> Self {
1287 Self::DEFAULT
1288 }
1289}
1290#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1291#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1292#[cfg_attr(feature = "serde", serde(tag = "type"))]
1293#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1294#[repr(u32)]
1295#[doc = "Enumeration of possible mount operation modes. This message is used by obsolete/deprecated gimbal messages."]
1296pub enum MavMountMode {
1297 #[doc = "Load and keep safe position (Roll,Pitch,Yaw) from permanent memory and stop stabilization"]
1298 MAV_MOUNT_MODE_RETRACT = 0,
1299 #[doc = "Load and keep neutral position (Roll,Pitch,Yaw) from permanent memory."]
1300 MAV_MOUNT_MODE_NEUTRAL = 1,
1301 #[doc = "Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization"]
1302 MAV_MOUNT_MODE_MAVLINK_TARGETING = 2,
1303 #[doc = "Load neutral position and start RC Roll,Pitch,Yaw control with stabilization"]
1304 MAV_MOUNT_MODE_RC_TARGETING = 3,
1305 #[doc = "Load neutral position and start to point to Lat,Lon,Alt"]
1306 MAV_MOUNT_MODE_GPS_POINT = 4,
1307 #[doc = "Gimbal tracks system with specified system ID"]
1308 MAV_MOUNT_MODE_SYSID_TARGET = 5,
1309 #[doc = "Gimbal tracks home position"]
1310 MAV_MOUNT_MODE_HOME_LOCATION = 6,
1311}
1312impl MavMountMode {
1313 pub const DEFAULT: Self = Self::MAV_MOUNT_MODE_RETRACT;
1314}
1315impl Default for MavMountMode {
1316 fn default() -> Self {
1317 Self::DEFAULT
1318 }
1319}
1320#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1321#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1322#[cfg_attr(feature = "serde", serde(tag = "type"))]
1323#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1324#[repr(u32)]
1325#[doc = "Source of information about this collision."]
1326pub enum MavCollisionSrc {
1327 #[doc = "ID field references ADSB_VEHICLE packets"]
1328 MAV_COLLISION_SRC_ADSB = 0,
1329 #[doc = "ID field references MAVLink SRC ID"]
1330 MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT = 1,
1331}
1332impl MavCollisionSrc {
1333 pub const DEFAULT: Self = Self::MAV_COLLISION_SRC_ADSB;
1334}
1335impl Default for MavCollisionSrc {
1336 fn default() -> Self {
1337 Self::DEFAULT
1338 }
1339}
1340#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1341#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1342#[cfg_attr(feature = "serde", serde(tag = "type"))]
1343#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1344#[repr(u32)]
1345#[doc = "GPS longitudinal offset encoding"]
1346pub enum UavionixAdsbOutCfgGpsOffsetLon {
1347 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA = 0,
1348 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_APPLIED_BY_SENSOR = 1,
1349}
1350impl UavionixAdsbOutCfgGpsOffsetLon {
1351 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LON_NO_DATA;
1352}
1353impl Default for UavionixAdsbOutCfgGpsOffsetLon {
1354 fn default() -> Self {
1355 Self::DEFAULT
1356 }
1357}
1358bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "SERIAL_CONTROL flags (bitmask)"] pub struct SerialControlFlag : u8 { # [doc = "Set if this is a reply"] const SERIAL_CONTROL_FLAG_REPLY = 1 ; # [doc = "Set if the sender wants the receiver to send a response as another SERIAL_CONTROL message"] const SERIAL_CONTROL_FLAG_RESPOND = 2 ; # [doc = "Set if access to the serial port should be removed from whatever driver is currently using it, giving exclusive access to the SERIAL_CONTROL protocol. The port can be handed back by sending a request without this flag set"] const SERIAL_CONTROL_FLAG_EXCLUSIVE = 4 ; # [doc = "Block on writes to the serial port"] const SERIAL_CONTROL_FLAG_BLOCKING = 8 ; # [doc = "Send multiple replies until port is drained"] const SERIAL_CONTROL_FLAG_MULTI = 16 ; } }
1359impl SerialControlFlag {
1360 pub const DEFAULT: Self = Self::SERIAL_CONTROL_FLAG_REPLY;
1361}
1362impl Default for SerialControlFlag {
1363 fn default() -> Self {
1364 Self::DEFAULT
1365 }
1366}
1367#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1368#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1369#[cfg_attr(feature = "serde", serde(tag = "type"))]
1370#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1371#[repr(u32)]
1372#[doc = "Possible safety switch states."]
1373pub enum SafetySwitchState {
1374 #[doc = "Safety switch is engaged and vehicle should be safe to approach."]
1375 SAFETY_SWITCH_STATE_SAFE = 0,
1376 #[doc = "Safety switch is NOT engaged and motors, propellers and other actuators should be considered active."]
1377 SAFETY_SWITCH_STATE_DANGEROUS = 1,
1378}
1379impl SafetySwitchState {
1380 pub const DEFAULT: Self = Self::SAFETY_SWITCH_STATE_SAFE;
1381}
1382impl Default for SafetySwitchState {
1383 fn default() -> Self {
1384 Self::DEFAULT
1385 }
1386}
1387#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1388#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1389#[cfg_attr(feature = "serde", serde(tag = "type"))]
1390#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1391#[repr(u32)]
1392#[doc = "These values define the type of firmware release. These values indicate the first version or release of this type. For example the first alpha release would be 64, the second would be 65."]
1393pub enum FirmwareVersionType {
1394 #[doc = "development release"]
1395 FIRMWARE_VERSION_TYPE_DEV = 0,
1396 #[doc = "alpha release"]
1397 FIRMWARE_VERSION_TYPE_ALPHA = 64,
1398 #[doc = "beta release"]
1399 FIRMWARE_VERSION_TYPE_BETA = 128,
1400 #[doc = "release candidate"]
1401 FIRMWARE_VERSION_TYPE_RC = 192,
1402 #[doc = "official stable release"]
1403 FIRMWARE_VERSION_TYPE_OFFICIAL = 255,
1404}
1405impl FirmwareVersionType {
1406 pub const DEFAULT: Self = Self::FIRMWARE_VERSION_TYPE_DEV;
1407}
1408impl Default for FirmwareVersionType {
1409 fn default() -> Self {
1410 Self::DEFAULT
1411 }
1412}
1413bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Stream status flags (Bitmap)"] pub struct VideoStreamStatusFlags : u16 { # [doc = "Stream is active (running)"] const VIDEO_STREAM_STATUS_FLAGS_RUNNING = 1 ; # [doc = "Stream is thermal imaging"] const VIDEO_STREAM_STATUS_FLAGS_THERMAL = 2 ; # [doc = "Stream can report absolute thermal range (see CAMERA_THERMAL_RANGE)."] const VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED = 4 ; } }
1414impl VideoStreamStatusFlags {
1415 pub const DEFAULT: Self = Self::VIDEO_STREAM_STATUS_FLAGS_RUNNING;
1416}
1417impl Default for VideoStreamStatusFlags {
1418 fn default() -> Self {
1419 Self::DEFAULT
1420 }
1421}
1422#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1423#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1424#[cfg_attr(feature = "serde", serde(tag = "type"))]
1425#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1426#[repr(u32)]
1427#[doc = "Enumeration of landed detector states"]
1428pub enum MavLandedState {
1429 #[doc = "MAV landed state is unknown"]
1430 MAV_LANDED_STATE_UNDEFINED = 0,
1431 #[doc = "MAV is landed (on ground)"]
1432 MAV_LANDED_STATE_ON_GROUND = 1,
1433 #[doc = "MAV is in air"]
1434 MAV_LANDED_STATE_IN_AIR = 2,
1435 #[doc = "MAV currently taking off"]
1436 MAV_LANDED_STATE_TAKEOFF = 3,
1437 #[doc = "MAV currently landing"]
1438 MAV_LANDED_STATE_LANDING = 4,
1439}
1440impl MavLandedState {
1441 pub const DEFAULT: Self = Self::MAV_LANDED_STATE_UNDEFINED;
1442}
1443impl Default for MavLandedState {
1444 fn default() -> Self {
1445 Self::DEFAULT
1446 }
1447}
1448bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message."] pub struct MavSysStatusSensor : u32 { # [doc = "0x01 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO = 1 ; # [doc = "0x02 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL = 2 ; # [doc = "0x04 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG = 4 ; # [doc = "0x08 absolute pressure"] const MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE = 8 ; # [doc = "0x10 differential pressure"] const MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE = 16 ; # [doc = "0x20 GPS"] const MAV_SYS_STATUS_SENSOR_GPS = 32 ; # [doc = "0x40 optical flow"] const MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW = 64 ; # [doc = "0x80 computer vision position"] const MAV_SYS_STATUS_SENSOR_VISION_POSITION = 128 ; # [doc = "0x100 laser based position"] const MAV_SYS_STATUS_SENSOR_LASER_POSITION = 256 ; # [doc = "0x200 external ground truth (Vicon or Leica)"] const MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH = 512 ; # [doc = "0x400 3D angular rate control"] const MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL = 1024 ; # [doc = "0x800 attitude stabilization"] const MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION = 2048 ; # [doc = "0x1000 yaw position"] const MAV_SYS_STATUS_SENSOR_YAW_POSITION = 4096 ; # [doc = "0x2000 z/altitude control"] const MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL = 8192 ; # [doc = "0x4000 x/y position control"] const MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL = 16384 ; # [doc = "0x8000 motor outputs / control"] const MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS = 32768 ; # [doc = "0x10000 RC receiver"] const MAV_SYS_STATUS_SENSOR_RC_RECEIVER = 65536 ; # [doc = "0x20000 2nd 3D gyro"] const MAV_SYS_STATUS_SENSOR_3D_GYRO2 = 131072 ; # [doc = "0x40000 2nd 3D accelerometer"] const MAV_SYS_STATUS_SENSOR_3D_ACCEL2 = 262144 ; # [doc = "0x80000 2nd 3D magnetometer"] const MAV_SYS_STATUS_SENSOR_3D_MAG2 = 524288 ; # [doc = "0x100000 geofence"] const MAV_SYS_STATUS_GEOFENCE = 1048576 ; # [doc = "0x200000 AHRS subsystem health"] const MAV_SYS_STATUS_AHRS = 2097152 ; # [doc = "0x400000 Terrain subsystem health"] const MAV_SYS_STATUS_TERRAIN = 4194304 ; # [doc = "0x800000 Motors are reversed"] const MAV_SYS_STATUS_REVERSE_MOTOR = 8388608 ; # [doc = "0x1000000 Logging"] const MAV_SYS_STATUS_LOGGING = 16777216 ; # [doc = "0x2000000 Battery"] const MAV_SYS_STATUS_SENSOR_BATTERY = 33554432 ; # [doc = "0x4000000 Proximity"] const MAV_SYS_STATUS_SENSOR_PROXIMITY = 67108864 ; # [doc = "0x8000000 Satellite Communication"] const MAV_SYS_STATUS_SENSOR_SATCOM = 134217728 ; # [doc = "0x10000000 pre-arm check status. Always healthy when armed"] const MAV_SYS_STATUS_PREARM_CHECK = 268435456 ; # [doc = "0x20000000 Avoidance/collision prevention"] const MAV_SYS_STATUS_OBSTACLE_AVOIDANCE = 536870912 ; # [doc = "0x40000000 propulsion (actuator, esc, motor or propellor)"] const MAV_SYS_STATUS_SENSOR_PROPULSION = 1073741824 ; # [doc = "0x80000000 Extended bit-field are used for further sensor status bits (needs to be set in onboard_control_sensors_present only)"] const MAV_SYS_STATUS_EXTENSION_USED = 2147483648 ; } }
1449impl MavSysStatusSensor {
1450 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_SENSOR_3D_GYRO;
1451}
1452impl Default for MavSysStatusSensor {
1453 fn default() -> Self {
1454 Self::DEFAULT
1455 }
1456}
1457#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1458#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1459#[cfg_attr(feature = "serde", serde(tag = "type"))]
1460#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1461#[repr(u32)]
1462#[doc = "Generalized UAVCAN node mode"]
1463pub enum UavcanNodeMode {
1464 #[doc = "The node is performing its primary functions."]
1465 UAVCAN_NODE_MODE_OPERATIONAL = 0,
1466 #[doc = "The node is initializing; this mode is entered immediately after startup."]
1467 UAVCAN_NODE_MODE_INITIALIZATION = 1,
1468 #[doc = "The node is under maintenance."]
1469 UAVCAN_NODE_MODE_MAINTENANCE = 2,
1470 #[doc = "The node is in the process of updating its software."]
1471 UAVCAN_NODE_MODE_SOFTWARE_UPDATE = 3,
1472 #[doc = "The node is no longer available online."]
1473 UAVCAN_NODE_MODE_OFFLINE = 7,
1474}
1475impl UavcanNodeMode {
1476 pub const DEFAULT: Self = Self::UAVCAN_NODE_MODE_OPERATIONAL;
1477}
1478impl Default for UavcanNodeMode {
1479 fn default() -> Self {
1480 Self::DEFAULT
1481 }
1482}
1483#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1484#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1485#[cfg_attr(feature = "serde", serde(tag = "type"))]
1486#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1487#[repr(u32)]
1488#[doc = "Video stream types"]
1489pub enum VideoStreamType {
1490 #[doc = "Stream is RTSP"]
1491 VIDEO_STREAM_TYPE_RTSP = 0,
1492 #[doc = "Stream is RTP UDP (URI gives the port number)"]
1493 VIDEO_STREAM_TYPE_RTPUDP = 1,
1494 #[doc = "Stream is MPEG on TCP"]
1495 VIDEO_STREAM_TYPE_TCP_MPEG = 2,
1496 #[doc = "Stream is MPEG TS (URI gives the port number)"]
1497 VIDEO_STREAM_TYPE_MPEG_TS = 3,
1498}
1499impl VideoStreamType {
1500 pub const DEFAULT: Self = Self::VIDEO_STREAM_TYPE_RTSP;
1501}
1502impl Default for VideoStreamType {
1503 fn default() -> Self {
1504 Self::DEFAULT
1505 }
1506}
1507#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1508#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1509#[cfg_attr(feature = "serde", serde(tag = "type"))]
1510#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1511#[repr(u32)]
1512#[doc = "Flags to indicate the type of storage."]
1513pub enum StorageType {
1514 #[doc = "Storage type is not known."]
1515 STORAGE_TYPE_UNKNOWN = 0,
1516 #[doc = "Storage type is USB device."]
1517 STORAGE_TYPE_USB_STICK = 1,
1518 #[doc = "Storage type is SD card."]
1519 STORAGE_TYPE_SD = 2,
1520 #[doc = "Storage type is microSD card."]
1521 STORAGE_TYPE_MICROSD = 3,
1522 #[doc = "Storage type is CFast."]
1523 STORAGE_TYPE_CF = 4,
1524 #[doc = "Storage type is CFexpress."]
1525 STORAGE_TYPE_CFE = 5,
1526 #[doc = "Storage type is XQD."]
1527 STORAGE_TYPE_XQD = 6,
1528 #[doc = "Storage type is HD mass storage type."]
1529 STORAGE_TYPE_HD = 7,
1530 #[doc = "Storage type is other, not listed type."]
1531 STORAGE_TYPE_OTHER = 254,
1532}
1533impl StorageType {
1534 pub const DEFAULT: Self = Self::STORAGE_TYPE_UNKNOWN;
1535}
1536impl Default for StorageType {
1537 fn default() -> Self {
1538 Self::DEFAULT
1539 }
1540}
1541#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1542#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1543#[cfg_attr(feature = "serde", serde(tag = "type"))]
1544#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1545#[repr(u32)]
1546#[doc = "States of the mission state machine. Note that these states are independent of whether the mission is in a mode that can execute mission items or not (is suspended). They may not all be relevant on all vehicles."]
1547pub enum MissionState {
1548 #[doc = "The mission status reporting is not supported."]
1549 MISSION_STATE_UNKNOWN = 0,
1550 #[doc = "No mission on the vehicle."]
1551 MISSION_STATE_NO_MISSION = 1,
1552 #[doc = "Mission has not started. This is the case after a mission has uploaded but not yet started executing."]
1553 MISSION_STATE_NOT_STARTED = 2,
1554 #[doc = "Mission is active, and will execute mission items when in auto mode."]
1555 MISSION_STATE_ACTIVE = 3,
1556 #[doc = "Mission is paused when in auto mode."]
1557 MISSION_STATE_PAUSED = 4,
1558 #[doc = "Mission has executed all mission items."]
1559 MISSION_STATE_COMPLETE = 5,
1560}
1561impl MissionState {
1562 pub const DEFAULT: Self = Self::MISSION_STATE_UNKNOWN;
1563}
1564impl Default for MissionState {
1565 fn default() -> Self {
1566 Self::DEFAULT
1567 }
1568}
1569#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1570#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1571#[cfg_attr(feature = "serde", serde(tag = "type"))]
1572#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1573#[repr(u32)]
1574#[doc = "List of possible units where failures can be injected."]
1575pub enum FailureUnit {
1576 FAILURE_UNIT_SENSOR_GYRO = 0,
1577 FAILURE_UNIT_SENSOR_ACCEL = 1,
1578 FAILURE_UNIT_SENSOR_MAG = 2,
1579 FAILURE_UNIT_SENSOR_BARO = 3,
1580 FAILURE_UNIT_SENSOR_GPS = 4,
1581 FAILURE_UNIT_SENSOR_OPTICAL_FLOW = 5,
1582 FAILURE_UNIT_SENSOR_VIO = 6,
1583 FAILURE_UNIT_SENSOR_DISTANCE_SENSOR = 7,
1584 FAILURE_UNIT_SENSOR_AIRSPEED = 8,
1585 FAILURE_UNIT_SYSTEM_BATTERY = 100,
1586 FAILURE_UNIT_SYSTEM_MOTOR = 101,
1587 FAILURE_UNIT_SYSTEM_SERVO = 102,
1588 FAILURE_UNIT_SYSTEM_AVOIDANCE = 103,
1589 FAILURE_UNIT_SYSTEM_RC_SIGNAL = 104,
1590 FAILURE_UNIT_SYSTEM_MAVLINK_SIGNAL = 105,
1591}
1592impl FailureUnit {
1593 pub const DEFAULT: Self = Self::FAILURE_UNIT_SENSOR_GYRO;
1594}
1595impl Default for FailureUnit {
1596 fn default() -> Self {
1597 Self::DEFAULT
1598 }
1599}
1600#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1601#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1602#[cfg_attr(feature = "serde", serde(tag = "type"))]
1603#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1604#[repr(u32)]
1605pub enum MavArmAuthDeniedReason {
1606 #[doc = "Not a specific reason"]
1607 MAV_ARM_AUTH_DENIED_REASON_GENERIC = 0,
1608 #[doc = "Authorizer will send the error as string to GCS"]
1609 MAV_ARM_AUTH_DENIED_REASON_NONE = 1,
1610 #[doc = "At least one waypoint have a invalid value"]
1611 MAV_ARM_AUTH_DENIED_REASON_INVALID_WAYPOINT = 2,
1612 #[doc = "Timeout in the authorizer process(in case it depends on network)"]
1613 MAV_ARM_AUTH_DENIED_REASON_TIMEOUT = 3,
1614 #[doc = "Airspace of the mission in use by another vehicle, second result parameter can have the waypoint id that caused it to be denied."]
1615 MAV_ARM_AUTH_DENIED_REASON_AIRSPACE_IN_USE = 4,
1616 #[doc = "Weather is not good to fly"]
1617 MAV_ARM_AUTH_DENIED_REASON_BAD_WEATHER = 5,
1618}
1619impl MavArmAuthDeniedReason {
1620 pub const DEFAULT: Self = Self::MAV_ARM_AUTH_DENIED_REASON_GENERIC;
1621}
1622impl Default for MavArmAuthDeniedReason {
1623 fn default() -> Self {
1624 Self::DEFAULT
1625 }
1626}
1627#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1628#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1629#[cfg_attr(feature = "serde", serde(tag = "type"))]
1630#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1631#[repr(u32)]
1632pub enum MavOdidArmStatus {
1633 #[doc = "Passing arming checks."]
1634 MAV_ODID_ARM_STATUS_GOOD_TO_ARM = 0,
1635 #[doc = "Generic arming failure, see error string for details."]
1636 MAV_ODID_ARM_STATUS_PRE_ARM_FAIL_GENERIC = 1,
1637}
1638impl MavOdidArmStatus {
1639 pub const DEFAULT: Self = Self::MAV_ODID_ARM_STATUS_GOOD_TO_ARM;
1640}
1641impl Default for MavOdidArmStatus {
1642 fn default() -> Self {
1643 Self::DEFAULT
1644 }
1645}
1646#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1647#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1648#[cfg_attr(feature = "serde", serde(tag = "type"))]
1649#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1650#[repr(u32)]
1651pub enum NavVtolLandOptions {
1652 #[doc = "Default autopilot landing behaviour."]
1653 NAV_VTOL_LAND_OPTIONS_DEFAULT = 0,
1654 #[doc = "Descend in fixed wing mode, transitioning to multicopter mode for vertical landing when close to the ground. The fixed wing descent pattern is at the discretion of the vehicle (e.g. transition altitude, loiter direction, radius, and speed, etc.)."]
1655 NAV_VTOL_LAND_OPTIONS_FW_DESCENT = 1,
1656 #[doc = "Land in multicopter mode on reaching the landing coordinates (the whole landing is by \"hover descent\")."]
1657 NAV_VTOL_LAND_OPTIONS_HOVER_DESCENT = 2,
1658}
1659impl NavVtolLandOptions {
1660 pub const DEFAULT: Self = Self::NAV_VTOL_LAND_OPTIONS_DEFAULT;
1661}
1662impl Default for NavVtolLandOptions {
1663 fn default() -> Self {
1664 Self::DEFAULT
1665 }
1666}
1667#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1668#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1669#[cfg_attr(feature = "serde", serde(tag = "type"))]
1670#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1671#[repr(u32)]
1672#[doc = "Type of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
1673pub enum AisType {
1674 #[doc = "Not available (default)."]
1675 AIS_TYPE_UNKNOWN = 0,
1676 AIS_TYPE_RESERVED_1 = 1,
1677 AIS_TYPE_RESERVED_2 = 2,
1678 AIS_TYPE_RESERVED_3 = 3,
1679 AIS_TYPE_RESERVED_4 = 4,
1680 AIS_TYPE_RESERVED_5 = 5,
1681 AIS_TYPE_RESERVED_6 = 6,
1682 AIS_TYPE_RESERVED_7 = 7,
1683 AIS_TYPE_RESERVED_8 = 8,
1684 AIS_TYPE_RESERVED_9 = 9,
1685 AIS_TYPE_RESERVED_10 = 10,
1686 AIS_TYPE_RESERVED_11 = 11,
1687 AIS_TYPE_RESERVED_12 = 12,
1688 AIS_TYPE_RESERVED_13 = 13,
1689 AIS_TYPE_RESERVED_14 = 14,
1690 AIS_TYPE_RESERVED_15 = 15,
1691 AIS_TYPE_RESERVED_16 = 16,
1692 AIS_TYPE_RESERVED_17 = 17,
1693 AIS_TYPE_RESERVED_18 = 18,
1694 AIS_TYPE_RESERVED_19 = 19,
1695 #[doc = "Wing In Ground effect."]
1696 AIS_TYPE_WIG = 20,
1697 AIS_TYPE_WIG_HAZARDOUS_A = 21,
1698 AIS_TYPE_WIG_HAZARDOUS_B = 22,
1699 AIS_TYPE_WIG_HAZARDOUS_C = 23,
1700 AIS_TYPE_WIG_HAZARDOUS_D = 24,
1701 AIS_TYPE_WIG_RESERVED_1 = 25,
1702 AIS_TYPE_WIG_RESERVED_2 = 26,
1703 AIS_TYPE_WIG_RESERVED_3 = 27,
1704 AIS_TYPE_WIG_RESERVED_4 = 28,
1705 AIS_TYPE_WIG_RESERVED_5 = 29,
1706 AIS_TYPE_FISHING = 30,
1707 AIS_TYPE_TOWING = 31,
1708 #[doc = "Towing: length exceeds 200m or breadth exceeds 25m."]
1709 AIS_TYPE_TOWING_LARGE = 32,
1710 #[doc = "Dredging or other underwater ops."]
1711 AIS_TYPE_DREDGING = 33,
1712 AIS_TYPE_DIVING = 34,
1713 AIS_TYPE_MILITARY = 35,
1714 AIS_TYPE_SAILING = 36,
1715 AIS_TYPE_PLEASURE = 37,
1716 AIS_TYPE_RESERVED_20 = 38,
1717 AIS_TYPE_RESERVED_21 = 39,
1718 #[doc = "High Speed Craft."]
1719 AIS_TYPE_HSC = 40,
1720 AIS_TYPE_HSC_HAZARDOUS_A = 41,
1721 AIS_TYPE_HSC_HAZARDOUS_B = 42,
1722 AIS_TYPE_HSC_HAZARDOUS_C = 43,
1723 AIS_TYPE_HSC_HAZARDOUS_D = 44,
1724 AIS_TYPE_HSC_RESERVED_1 = 45,
1725 AIS_TYPE_HSC_RESERVED_2 = 46,
1726 AIS_TYPE_HSC_RESERVED_3 = 47,
1727 AIS_TYPE_HSC_RESERVED_4 = 48,
1728 AIS_TYPE_HSC_UNKNOWN = 49,
1729 AIS_TYPE_PILOT = 50,
1730 #[doc = "Search And Rescue vessel."]
1731 AIS_TYPE_SAR = 51,
1732 AIS_TYPE_TUG = 52,
1733 AIS_TYPE_PORT_TENDER = 53,
1734 #[doc = "Anti-pollution equipment."]
1735 AIS_TYPE_ANTI_POLLUTION = 54,
1736 AIS_TYPE_LAW_ENFORCEMENT = 55,
1737 AIS_TYPE_SPARE_LOCAL_1 = 56,
1738 AIS_TYPE_SPARE_LOCAL_2 = 57,
1739 AIS_TYPE_MEDICAL_TRANSPORT = 58,
1740 #[doc = "Noncombatant ship according to RR Resolution No. 18."]
1741 AIS_TYPE_NONECOMBATANT = 59,
1742 AIS_TYPE_PASSENGER = 60,
1743 AIS_TYPE_PASSENGER_HAZARDOUS_A = 61,
1744 AIS_TYPE_PASSENGER_HAZARDOUS_B = 62,
1745 AIS_TYPE_PASSENGER_HAZARDOUS_C = 63,
1746 AIS_TYPE_PASSENGER_HAZARDOUS_D = 64,
1747 AIS_TYPE_PASSENGER_RESERVED_1 = 65,
1748 AIS_TYPE_PASSENGER_RESERVED_2 = 66,
1749 AIS_TYPE_PASSENGER_RESERVED_3 = 67,
1750 AIS_TYPE_PASSENGER_RESERVED_4 = 68,
1751 AIS_TYPE_PASSENGER_UNKNOWN = 69,
1752 AIS_TYPE_CARGO = 70,
1753 AIS_TYPE_CARGO_HAZARDOUS_A = 71,
1754 AIS_TYPE_CARGO_HAZARDOUS_B = 72,
1755 AIS_TYPE_CARGO_HAZARDOUS_C = 73,
1756 AIS_TYPE_CARGO_HAZARDOUS_D = 74,
1757 AIS_TYPE_CARGO_RESERVED_1 = 75,
1758 AIS_TYPE_CARGO_RESERVED_2 = 76,
1759 AIS_TYPE_CARGO_RESERVED_3 = 77,
1760 AIS_TYPE_CARGO_RESERVED_4 = 78,
1761 AIS_TYPE_CARGO_UNKNOWN = 79,
1762 AIS_TYPE_TANKER = 80,
1763 AIS_TYPE_TANKER_HAZARDOUS_A = 81,
1764 AIS_TYPE_TANKER_HAZARDOUS_B = 82,
1765 AIS_TYPE_TANKER_HAZARDOUS_C = 83,
1766 AIS_TYPE_TANKER_HAZARDOUS_D = 84,
1767 AIS_TYPE_TANKER_RESERVED_1 = 85,
1768 AIS_TYPE_TANKER_RESERVED_2 = 86,
1769 AIS_TYPE_TANKER_RESERVED_3 = 87,
1770 AIS_TYPE_TANKER_RESERVED_4 = 88,
1771 AIS_TYPE_TANKER_UNKNOWN = 89,
1772 AIS_TYPE_OTHER = 90,
1773 AIS_TYPE_OTHER_HAZARDOUS_A = 91,
1774 AIS_TYPE_OTHER_HAZARDOUS_B = 92,
1775 AIS_TYPE_OTHER_HAZARDOUS_C = 93,
1776 AIS_TYPE_OTHER_HAZARDOUS_D = 94,
1777 AIS_TYPE_OTHER_RESERVED_1 = 95,
1778 AIS_TYPE_OTHER_RESERVED_2 = 96,
1779 AIS_TYPE_OTHER_RESERVED_3 = 97,
1780 AIS_TYPE_OTHER_RESERVED_4 = 98,
1781 AIS_TYPE_OTHER_UNKNOWN = 99,
1782}
1783impl AisType {
1784 pub const DEFAULT: Self = Self::AIS_TYPE_UNKNOWN;
1785}
1786impl Default for AisType {
1787 fn default() -> Self {
1788 Self::DEFAULT
1789 }
1790}
1791#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1792#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1793#[cfg_attr(feature = "serde", serde(tag = "type"))]
1794#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1795#[repr(u32)]
1796#[doc = "GPS lataral offset encoding"]
1797pub enum UavionixAdsbOutCfgGpsOffsetLat {
1798 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA = 0,
1799 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_2M = 1,
1800 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_4M = 2,
1801 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_LEFT_6M = 3,
1802 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_0M = 4,
1803 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_2M = 5,
1804 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_4M = 6,
1805 UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_RIGHT_6M = 7,
1806}
1807impl UavionixAdsbOutCfgGpsOffsetLat {
1808 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CFG_GPS_OFFSET_LAT_NO_DATA;
1809}
1810impl Default for UavionixAdsbOutCfgGpsOffsetLat {
1811 fn default() -> Self {
1812 Self::DEFAULT
1813 }
1814}
1815#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1816#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1817#[cfg_attr(feature = "serde", serde(tag = "type"))]
1818#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1819#[repr(u32)]
1820#[doc = "Possible responses from a CELLULAR_CONFIG message."]
1821pub enum CellularConfigResponse {
1822 #[doc = "Changes accepted."]
1823 CELLULAR_CONFIG_RESPONSE_ACCEPTED = 0,
1824 #[doc = "Invalid APN."]
1825 CELLULAR_CONFIG_RESPONSE_APN_ERROR = 1,
1826 #[doc = "Invalid PIN."]
1827 CELLULAR_CONFIG_RESPONSE_PIN_ERROR = 2,
1828 #[doc = "Changes rejected."]
1829 CELLULAR_CONFIG_RESPONSE_REJECTED = 3,
1830 #[doc = "PUK is required to unblock SIM card."]
1831 CELLULAR_CONFIG_BLOCKED_PUK_REQUIRED = 4,
1832}
1833impl CellularConfigResponse {
1834 pub const DEFAULT: Self = Self::CELLULAR_CONFIG_RESPONSE_ACCEPTED;
1835}
1836impl Default for CellularConfigResponse {
1837 fn default() -> Self {
1838 Self::DEFAULT
1839 }
1840}
1841bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for gimbal device (lower level) operation."] pub struct GimbalDeviceFlags : u16 { # [doc = "Set to retracted safe position (no stabilization), takes precedence over all other flags."] const GIMBAL_DEVICE_FLAGS_RETRACT = 1 ; # [doc = "Set to neutral/default position, taking precedence over all other flags except RETRACT. Neutral is commonly forward-facing and horizontal (roll=pitch=yaw=0) but may be any orientation."] const GIMBAL_DEVICE_FLAGS_NEUTRAL = 2 ; # [doc = "Lock roll angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_ROLL_LOCK = 4 ; # [doc = "Lock pitch angle to absolute angle relative to horizon (not relative to vehicle). This is generally the default with a stabilizing gimbal."] const GIMBAL_DEVICE_FLAGS_PITCH_LOCK = 8 ; # [doc = "Lock yaw angle to absolute angle relative to North (not relative to vehicle). If this flag is set, the yaw angle and z component of angular velocity are relative to North (earth frame, x-axis pointing North), else they are relative to the vehicle heading (vehicle frame, earth frame rotated so that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_LOCK = 16 ; # [doc = "Yaw angle and z component of angular velocity are relative to the vehicle heading (vehicle frame, earth frame rotated such that the x-axis is pointing forward)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Yaw angle and z component of angular velocity are relative to North (earth frame, x-axis is pointing North)."] const GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Gimbal device can accept yaw angle inputs relative to North (earth frame). This flag is only for reporting (attempts to set this flag are ignored)."] const GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "The gimbal orientation is set exclusively by the RC signals feed to the gimbal's radio control inputs. MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE) are ignored."] const GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "The gimbal orientation is determined by combining/mixing the RC signals feed to the gimbal's radio control inputs and the MAVLink messages for setting the gimbal orientation (GIMBAL_DEVICE_SET_ATTITUDE). How these two controls are combined or mixed is not defined by the protocol but is up to the implementation."] const GIMBAL_DEVICE_FLAGS_RC_MIXED = 512 ; } }
1842impl GimbalDeviceFlags {
1843 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_FLAGS_RETRACT;
1844}
1845impl Default for GimbalDeviceFlags {
1846 fn default() -> Self {
1847 Self::DEFAULT
1848 }
1849}
1850#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1851#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1852#[cfg_attr(feature = "serde", serde(tag = "type"))]
1853#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1854#[repr(u32)]
1855pub enum MavlinkDataStreamType {
1856 MAVLINK_DATA_STREAM_IMG_JPEG = 0,
1857 MAVLINK_DATA_STREAM_IMG_BMP = 1,
1858 MAVLINK_DATA_STREAM_IMG_RAW8U = 2,
1859 MAVLINK_DATA_STREAM_IMG_RAW32U = 3,
1860 MAVLINK_DATA_STREAM_IMG_PGM = 4,
1861 MAVLINK_DATA_STREAM_IMG_PNG = 5,
1862}
1863impl MavlinkDataStreamType {
1864 pub const DEFAULT: Self = Self::MAVLINK_DATA_STREAM_IMG_JPEG;
1865}
1866impl Default for MavlinkDataStreamType {
1867 fn default() -> Self {
1868 Self::DEFAULT
1869 }
1870}
1871#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1872#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1873#[cfg_attr(feature = "serde", serde(tag = "type"))]
1874#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1875#[repr(u32)]
1876#[doc = "Type of GPS fix"]
1877pub enum GpsFixType {
1878 #[doc = "No GPS connected"]
1879 GPS_FIX_TYPE_NO_GPS = 0,
1880 #[doc = "No position information, GPS is connected"]
1881 GPS_FIX_TYPE_NO_FIX = 1,
1882 #[doc = "2D position"]
1883 GPS_FIX_TYPE_2D_FIX = 2,
1884 #[doc = "3D position"]
1885 GPS_FIX_TYPE_3D_FIX = 3,
1886 #[doc = "DGPS/SBAS aided 3D position"]
1887 GPS_FIX_TYPE_DGPS = 4,
1888 #[doc = "RTK float, 3D position"]
1889 GPS_FIX_TYPE_RTK_FLOAT = 5,
1890 #[doc = "RTK Fixed, 3D position"]
1891 GPS_FIX_TYPE_RTK_FIXED = 6,
1892 #[doc = "Static fixed, typically used for base stations"]
1893 GPS_FIX_TYPE_STATIC = 7,
1894 #[doc = "PPP, 3D position."]
1895 GPS_FIX_TYPE_PPP = 8,
1896}
1897impl GpsFixType {
1898 pub const DEFAULT: Self = Self::GPS_FIX_TYPE_NO_GPS;
1899}
1900impl Default for GpsFixType {
1901 fn default() -> Self {
1902 Self::DEFAULT
1903 }
1904}
1905#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1906#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1907#[cfg_attr(feature = "serde", serde(tag = "type"))]
1908#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1909#[repr(u32)]
1910#[doc = "Flags to indicate the status of camera storage."]
1911pub enum StorageStatus {
1912 #[doc = "Storage is missing (no microSD card loaded for example.)"]
1913 STORAGE_STATUS_EMPTY = 0,
1914 #[doc = "Storage present but unformatted."]
1915 STORAGE_STATUS_UNFORMATTED = 1,
1916 #[doc = "Storage present and ready."]
1917 STORAGE_STATUS_READY = 2,
1918 #[doc = "Camera does not supply storage status information. Capacity information in STORAGE_INFORMATION fields will be ignored."]
1919 STORAGE_STATUS_NOT_SUPPORTED = 3,
1920}
1921impl StorageStatus {
1922 pub const DEFAULT: Self = Self::STORAGE_STATUS_EMPTY;
1923}
1924impl Default for StorageStatus {
1925 fn default() -> Self {
1926 Self::DEFAULT
1927 }
1928}
1929#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1930#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1931#[cfg_attr(feature = "serde", serde(tag = "type"))]
1932#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1933#[repr(u32)]
1934#[doc = "Camera tracking status flags"]
1935pub enum CameraTrackingStatusFlags {
1936 #[doc = "Camera is not tracking"]
1937 CAMERA_TRACKING_STATUS_FLAGS_IDLE = 0,
1938 #[doc = "Camera is tracking"]
1939 CAMERA_TRACKING_STATUS_FLAGS_ACTIVE = 1,
1940 #[doc = "Camera tracking in error state"]
1941 CAMERA_TRACKING_STATUS_FLAGS_ERROR = 2,
1942}
1943impl CameraTrackingStatusFlags {
1944 pub const DEFAULT: Self = Self::CAMERA_TRACKING_STATUS_FLAGS_IDLE;
1945}
1946impl Default for CameraTrackingStatusFlags {
1947 fn default() -> Self {
1948 Self::DEFAULT
1949 }
1950}
1951#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1952#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1953#[cfg_attr(feature = "serde", serde(tag = "type"))]
1954#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1955#[repr(u32)]
1956pub enum CanFilterOp {
1957 CAN_FILTER_REPLACE = 0,
1958 CAN_FILTER_ADD = 1,
1959 CAN_FILTER_REMOVE = 2,
1960}
1961impl CanFilterOp {
1962 pub const DEFAULT: Self = Self::CAN_FILTER_REPLACE;
1963}
1964impl Default for CanFilterOp {
1965 fn default() -> Self {
1966 Self::DEFAULT
1967 }
1968}
1969#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1970#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1971#[cfg_attr(feature = "serde", serde(tag = "type"))]
1972#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1973#[repr(u32)]
1974pub enum MavOdidOperatorLocationType {
1975 #[doc = "The location/altitude of the operator is the same as the take-off location."]
1976 MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF = 0,
1977 #[doc = "The location/altitude of the operator is dynamic. E.g. based on live GNSS data."]
1978 MAV_ODID_OPERATOR_LOCATION_TYPE_LIVE_GNSS = 1,
1979 #[doc = "The location/altitude of the operator are fixed values."]
1980 MAV_ODID_OPERATOR_LOCATION_TYPE_FIXED = 2,
1981}
1982impl MavOdidOperatorLocationType {
1983 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF;
1984}
1985impl Default for MavOdidOperatorLocationType {
1986 fn default() -> Self {
1987 Self::DEFAULT
1988 }
1989}
1990#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
1991#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
1992#[cfg_attr(feature = "serde", serde(tag = "type"))]
1993#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
1994#[repr(u32)]
1995#[doc = "Gripper actions."]
1996pub enum GripperActions {
1997 #[doc = "Gripper release cargo."]
1998 GRIPPER_ACTION_RELEASE = 0,
1999 #[doc = "Gripper grab onto cargo."]
2000 GRIPPER_ACTION_GRAB = 1,
2001}
2002impl GripperActions {
2003 pub const DEFAULT: Self = Self::GRIPPER_ACTION_RELEASE;
2004}
2005impl Default for GripperActions {
2006 fn default() -> Self {
2007 Self::DEFAULT
2008 }
2009}
2010#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2011#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2012#[cfg_attr(feature = "serde", serde(tag = "type"))]
2013#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2014#[repr(u32)]
2015#[doc = "Supported component metadata types. These are used in the \"general\" metadata file returned by COMPONENT_METADATA to provide information about supported metadata types. The types are not used directly in MAVLink messages."]
2016pub enum CompMetadataType {
2017 #[doc = "General information about the component. General metadata includes information about other metadata types supported by the component. Files of this type must be supported, and must be downloadable from vehicle using a MAVLink FTP URI."]
2018 COMP_METADATA_TYPE_GENERAL = 0,
2019 #[doc = "Parameter meta data."]
2020 COMP_METADATA_TYPE_PARAMETER = 1,
2021 #[doc = "Meta data that specifies which commands and command parameters the vehicle supports. (WIP)"]
2022 COMP_METADATA_TYPE_COMMANDS = 2,
2023 #[doc = "Meta data that specifies external non-MAVLink peripherals."]
2024 COMP_METADATA_TYPE_PERIPHERALS = 3,
2025 #[doc = "Meta data for the events interface."]
2026 COMP_METADATA_TYPE_EVENTS = 4,
2027 #[doc = "Meta data for actuator configuration (motors, servos and vehicle geometry) and testing."]
2028 COMP_METADATA_TYPE_ACTUATORS = 5,
2029}
2030impl CompMetadataType {
2031 pub const DEFAULT: Self = Self::COMP_METADATA_TYPE_GENERAL;
2032}
2033impl Default for CompMetadataType {
2034 fn default() -> Self {
2035 Self::DEFAULT
2036 }
2037}
2038#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2039#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2040#[cfg_attr(feature = "serde", serde(tag = "type"))]
2041#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2042#[repr(u32)]
2043#[doc = "Generalized UAVCAN node health"]
2044pub enum UavcanNodeHealth {
2045 #[doc = "The node is functioning properly."]
2046 UAVCAN_NODE_HEALTH_OK = 0,
2047 #[doc = "A critical parameter went out of range or the node has encountered a minor failure."]
2048 UAVCAN_NODE_HEALTH_WARNING = 1,
2049 #[doc = "The node has encountered a major failure."]
2050 UAVCAN_NODE_HEALTH_ERROR = 2,
2051 #[doc = "The node has suffered a fatal malfunction."]
2052 UAVCAN_NODE_HEALTH_CRITICAL = 3,
2053}
2054impl UavcanNodeHealth {
2055 pub const DEFAULT: Self = Self::UAVCAN_NODE_HEALTH_OK;
2056}
2057impl Default for UavcanNodeHealth {
2058 fn default() -> Self {
2059 Self::DEFAULT
2060 }
2061}
2062#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2063#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2064#[cfg_attr(feature = "serde", serde(tag = "type"))]
2065#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2066#[repr(u32)]
2067pub enum MavOdidHorAcc {
2068 #[doc = "The horizontal accuracy is unknown."]
2069 MAV_ODID_HOR_ACC_UNKNOWN = 0,
2070 #[doc = "The horizontal accuracy is smaller than 10 Nautical Miles. 18.52 km."]
2071 MAV_ODID_HOR_ACC_10NM = 1,
2072 #[doc = "The horizontal accuracy is smaller than 4 Nautical Miles. 7.408 km."]
2073 MAV_ODID_HOR_ACC_4NM = 2,
2074 #[doc = "The horizontal accuracy is smaller than 2 Nautical Miles. 3.704 km."]
2075 MAV_ODID_HOR_ACC_2NM = 3,
2076 #[doc = "The horizontal accuracy is smaller than 1 Nautical Miles. 1.852 km."]
2077 MAV_ODID_HOR_ACC_1NM = 4,
2078 #[doc = "The horizontal accuracy is smaller than 0.5 Nautical Miles. 926 m."]
2079 MAV_ODID_HOR_ACC_0_5NM = 5,
2080 #[doc = "The horizontal accuracy is smaller than 0.3 Nautical Miles. 555.6 m."]
2081 MAV_ODID_HOR_ACC_0_3NM = 6,
2082 #[doc = "The horizontal accuracy is smaller than 0.1 Nautical Miles. 185.2 m."]
2083 MAV_ODID_HOR_ACC_0_1NM = 7,
2084 #[doc = "The horizontal accuracy is smaller than 0.05 Nautical Miles. 92.6 m."]
2085 MAV_ODID_HOR_ACC_0_05NM = 8,
2086 #[doc = "The horizontal accuracy is smaller than 30 meter."]
2087 MAV_ODID_HOR_ACC_30_METER = 9,
2088 #[doc = "The horizontal accuracy is smaller than 10 meter."]
2089 MAV_ODID_HOR_ACC_10_METER = 10,
2090 #[doc = "The horizontal accuracy is smaller than 3 meter."]
2091 MAV_ODID_HOR_ACC_3_METER = 11,
2092 #[doc = "The horizontal accuracy is smaller than 1 meter."]
2093 MAV_ODID_HOR_ACC_1_METER = 12,
2094}
2095impl MavOdidHorAcc {
2096 pub const DEFAULT: Self = Self::MAV_ODID_HOR_ACC_UNKNOWN;
2097}
2098impl Default for MavOdidHorAcc {
2099 fn default() -> Self {
2100 Self::DEFAULT
2101 }
2102}
2103#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2104#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2105#[cfg_attr(feature = "serde", serde(tag = "type"))]
2106#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2107#[repr(u32)]
2108#[doc = "Navigational status of AIS vessel, enum duplicated from AIS standard, <https://gpsd.gitlab.io/gpsd/AIVDM.html>"]
2109pub enum AisNavStatus {
2110 #[doc = "Under way using engine."]
2111 UNDER_WAY = 0,
2112 AIS_NAV_ANCHORED = 1,
2113 AIS_NAV_UN_COMMANDED = 2,
2114 AIS_NAV_RESTRICTED_MANOEUVERABILITY = 3,
2115 AIS_NAV_DRAUGHT_CONSTRAINED = 4,
2116 AIS_NAV_MOORED = 5,
2117 AIS_NAV_AGROUND = 6,
2118 AIS_NAV_FISHING = 7,
2119 AIS_NAV_SAILING = 8,
2120 AIS_NAV_RESERVED_HSC = 9,
2121 AIS_NAV_RESERVED_WIG = 10,
2122 AIS_NAV_RESERVED_1 = 11,
2123 AIS_NAV_RESERVED_2 = 12,
2124 AIS_NAV_RESERVED_3 = 13,
2125 #[doc = "Search And Rescue Transponder."]
2126 AIS_NAV_AIS_SART = 14,
2127 #[doc = "Not available (default)."]
2128 AIS_NAV_UNKNOWN = 15,
2129}
2130impl AisNavStatus {
2131 pub const DEFAULT: Self = Self::UNDER_WAY;
2132}
2133impl Default for AisNavStatus {
2134 fn default() -> Self {
2135 Self::DEFAULT
2136 }
2137}
2138#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2139#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2140#[cfg_attr(feature = "serde", serde(tag = "type"))]
2141#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2142#[repr(u32)]
2143pub enum MagCalStatus {
2144 MAG_CAL_NOT_STARTED = 0,
2145 MAG_CAL_WAITING_TO_START = 1,
2146 MAG_CAL_RUNNING_STEP_ONE = 2,
2147 MAG_CAL_RUNNING_STEP_TWO = 3,
2148 MAG_CAL_SUCCESS = 4,
2149 MAG_CAL_FAILED = 5,
2150 MAG_CAL_BAD_ORIENTATION = 6,
2151 MAG_CAL_BAD_RADIUS = 7,
2152}
2153impl MagCalStatus {
2154 pub const DEFAULT: Self = Self::MAG_CAL_NOT_STARTED;
2155}
2156impl Default for MagCalStatus {
2157 fn default() -> Self {
2158 Self::DEFAULT
2159 }
2160}
2161#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2162#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2163#[cfg_attr(feature = "serde", serde(tag = "type"))]
2164#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2165#[repr(u32)]
2166#[doc = "Actions for reading and writing plan information (mission, rally points, geofence) between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly missions are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
2167pub enum PreflightStorageMissionAction {
2168 #[doc = "Read current mission data from persistent storage"]
2169 MISSION_READ_PERSISTENT = 0,
2170 #[doc = "Write current mission data to persistent storage"]
2171 MISSION_WRITE_PERSISTENT = 1,
2172 #[doc = "Erase all mission data stored on the vehicle (both persistent and volatile storage)"]
2173 MISSION_RESET_DEFAULT = 2,
2174}
2175impl PreflightStorageMissionAction {
2176 pub const DEFAULT: Self = Self::MISSION_READ_PERSISTENT;
2177}
2178impl Default for PreflightStorageMissionAction {
2179 fn default() -> Self {
2180 Self::DEFAULT
2181 }
2182}
2183bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal device (low level) capability flags (bitmap)."] pub struct GimbalDeviceCapFlags : u16 { # [doc = "Gimbal device supports a retracted position."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Gimbal device supports a horizontal, forward looking position, stabilized."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Gimbal device supports rotating around roll axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Gimbal device supports to follow a roll angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Gimbal device supports locking to a roll angle (generally that's the default with roll stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Gimbal device supports rotating around pitch axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Gimbal device supports to follow a pitch angle relative to the vehicle."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Gimbal device supports locking to a pitch angle (generally that's the default with pitch stabilized)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Gimbal device supports rotating around yaw axis."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Gimbal device supports to follow a yaw angle relative to the vehicle (generally that's the default)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Gimbal device supports locking to an absolute heading, i.e., yaw angle relative to North (earth frame, often this is an option available)."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Gimbal device supports yawing/panning infinitely (e.g. using slip disk)."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Gimbal device supports yaw angles and angular velocities relative to North (earth frame). This usually requires support by an autopilot via AUTOPILOT_STATE_FOR_GIMBAL_DEVICE. Support can go on and off during runtime, which is reported by the flag GIMBAL_DEVICE_FLAGS_CAN_ACCEPT_YAW_IN_EARTH_FRAME."] const GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Gimbal device supports radio control inputs as an alternative input for controlling the gimbal orientation."] const GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; } }
2184impl GimbalDeviceCapFlags {
2185 pub const DEFAULT: Self = Self::GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT;
2186}
2187impl Default for GimbalDeviceCapFlags {
2188 fn default() -> Self {
2189 Self::DEFAULT
2190 }
2191}
2192#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2193#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2194#[cfg_attr(feature = "serde", serde(tag = "type"))]
2195#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2196#[repr(u32)]
2197#[doc = "Possible responses from a WIFI_CONFIG_AP message."]
2198pub enum WifiConfigApResponse {
2199 #[doc = "Undefined response. Likely an indicative of a system that doesn't support this request."]
2200 WIFI_CONFIG_AP_RESPONSE_UNDEFINED = 0,
2201 #[doc = "Changes accepted."]
2202 WIFI_CONFIG_AP_RESPONSE_ACCEPTED = 1,
2203 #[doc = "Changes rejected."]
2204 WIFI_CONFIG_AP_RESPONSE_REJECTED = 2,
2205 #[doc = "Invalid Mode."]
2206 WIFI_CONFIG_AP_RESPONSE_MODE_ERROR = 3,
2207 #[doc = "Invalid SSID."]
2208 WIFI_CONFIG_AP_RESPONSE_SSID_ERROR = 4,
2209 #[doc = "Invalid Password."]
2210 WIFI_CONFIG_AP_RESPONSE_PASSWORD_ERROR = 5,
2211}
2212impl WifiConfigApResponse {
2213 pub const DEFAULT: Self = Self::WIFI_CONFIG_AP_RESPONSE_UNDEFINED;
2214}
2215impl Default for WifiConfigApResponse {
2216 fn default() -> Self {
2217 Self::DEFAULT
2218 }
2219}
2220bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Status flags for ADS-B transponder dynamic output"] pub struct UavionixAdsbRfHealth : u8 { const UAVIONIX_ADSB_RF_HEALTH_OK = 1 ; const UAVIONIX_ADSB_RF_HEALTH_FAIL_TX = 2 ; const UAVIONIX_ADSB_RF_HEALTH_FAIL_RX = 16 ; } }
2221impl UavionixAdsbRfHealth {
2222 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_RF_HEALTH_OK;
2223}
2224impl Default for UavionixAdsbRfHealth {
2225 fn default() -> Self {
2226 Self::DEFAULT
2227 }
2228}
2229#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2230#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2231#[cfg_attr(feature = "serde", serde(tag = "type"))]
2232#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2233#[repr(u32)]
2234#[doc = "Emergency status encoding"]
2235pub enum UavionixAdsbEmergencyStatus {
2236 UAVIONIX_ADSB_OUT_NO_EMERGENCY = 0,
2237 UAVIONIX_ADSB_OUT_GENERAL_EMERGENCY = 1,
2238 UAVIONIX_ADSB_OUT_LIFEGUARD_EMERGENCY = 2,
2239 UAVIONIX_ADSB_OUT_MINIMUM_FUEL_EMERGENCY = 3,
2240 UAVIONIX_ADSB_OUT_NO_COMM_EMERGENCY = 4,
2241 UAVIONIX_ADSB_OUT_UNLAWFUL_INTERFERANCE_EMERGENCY = 5,
2242 UAVIONIX_ADSB_OUT_DOWNED_AIRCRAFT_EMERGENCY = 6,
2243 UAVIONIX_ADSB_OUT_RESERVED = 7,
2244}
2245impl UavionixAdsbEmergencyStatus {
2246 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_NO_EMERGENCY;
2247}
2248impl Default for UavionixAdsbEmergencyStatus {
2249 fn default() -> Self {
2250 Self::DEFAULT
2251 }
2252}
2253bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags encode the MAV mode."] pub struct MavModeFlag : u8 { # [doc = "0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. Additional note: this flag is to be ignore when sent in the command MAV_CMD_DO_SET_MODE and MAV_CMD_COMPONENT_ARM_DISARM shall be used instead. The flag can still be used to report the armed state."] const MAV_MODE_FLAG_SAFETY_ARMED = 128 ; # [doc = "0b01000000 remote control input is enabled."] const MAV_MODE_FLAG_MANUAL_INPUT_ENABLED = 64 ; # [doc = "0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational."] const MAV_MODE_FLAG_HIL_ENABLED = 32 ; # [doc = "0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around."] const MAV_MODE_FLAG_STABILIZE_ENABLED = 16 ; # [doc = "0b00001000 guided mode enabled, system flies waypoints / mission items."] const MAV_MODE_FLAG_GUIDED_ENABLED = 8 ; # [doc = "0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation."] const MAV_MODE_FLAG_AUTO_ENABLED = 4 ; # [doc = "0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations."] const MAV_MODE_FLAG_TEST_ENABLED = 2 ; # [doc = "0b00000001 Reserved for future use."] const MAV_MODE_FLAG_CUSTOM_MODE_ENABLED = 1 ; } }
2254impl MavModeFlag {
2255 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_SAFETY_ARMED;
2256}
2257impl Default for MavModeFlag {
2258 fn default() -> Self {
2259 Self::DEFAULT
2260 }
2261}
2262bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder dynamic report"] pub struct UavionixAdsbOutControlState : u8 { const UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED = 1 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_ON_GROUND = 4 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_IDENT_BUTTON_ACTIVE = 8 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_A_ENABLED = 16 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_C_ENABLED = 32 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_MODE_S_ENABLED = 64 ; const UAVIONIX_ADSB_OUT_CONTROL_STATE_1090ES_TX_ENABLED = 128 ; } }
2263impl UavionixAdsbOutControlState {
2264 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_CONTROL_STATE_EXTERNAL_BARO_CROSSCHECKED;
2265}
2266impl Default for UavionixAdsbOutControlState {
2267 fn default() -> Self {
2268 Self::DEFAULT
2269 }
2270}
2271#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2272#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2273#[cfg_attr(feature = "serde", serde(tag = "type"))]
2274#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2275#[repr(u32)]
2276#[doc = "MAV FTP error codes (<https://mavlink.io/en/services/ftp.html>)"]
2277pub enum MavFtpErr {
2278 #[doc = "None: No error"]
2279 MAV_FTP_ERR_NONE = 0,
2280 #[doc = "Fail: Unknown failure"]
2281 MAV_FTP_ERR_FAIL = 1,
2282 #[doc = "FailErrno: Command failed, Err number sent back in PayloadHeader.data[1]. \t\tThis is a file-system error number understood by the server operating system."]
2283 MAV_FTP_ERR_FAILERRNO = 2,
2284 #[doc = "InvalidDataSize: Payload size is invalid"]
2285 MAV_FTP_ERR_INVALIDDATASIZE = 3,
2286 #[doc = "InvalidSession: Session is not currently open"]
2287 MAV_FTP_ERR_INVALIDSESSION = 4,
2288 #[doc = "NoSessionsAvailable: All available sessions are already in use"]
2289 MAV_FTP_ERR_NOSESSIONSAVAILABLE = 5,
2290 #[doc = "EOF: Offset past end of file for ListDirectory and ReadFile commands"]
2291 MAV_FTP_ERR_EOF = 6,
2292 #[doc = "UnknownCommand: Unknown command / opcode"]
2293 MAV_FTP_ERR_UNKNOWNCOMMAND = 7,
2294 #[doc = "FileExists: File/directory already exists"]
2295 MAV_FTP_ERR_FILEEXISTS = 8,
2296 #[doc = "FileProtected: File/directory is write protected"]
2297 MAV_FTP_ERR_FILEPROTECTED = 9,
2298 #[doc = "FileNotFound: File/directory not found"]
2299 MAV_FTP_ERR_FILENOTFOUND = 10,
2300}
2301impl MavFtpErr {
2302 pub const DEFAULT: Self = Self::MAV_FTP_ERR_NONE;
2303}
2304impl Default for MavFtpErr {
2305 fn default() -> Self {
2306 Self::DEFAULT
2307 }
2308}
2309#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2310#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2311#[cfg_attr(feature = "serde", serde(tag = "type"))]
2312#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2313#[repr(u32)]
2314pub enum MavOdidOperatorIdType {
2315 #[doc = "CAA (Civil Aviation Authority) registered operator ID."]
2316 MAV_ODID_OPERATOR_ID_TYPE_CAA = 0,
2317}
2318impl MavOdidOperatorIdType {
2319 pub const DEFAULT: Self = Self::MAV_ODID_OPERATOR_ID_TYPE_CAA;
2320}
2321impl Default for MavOdidOperatorIdType {
2322 fn default() -> Self {
2323 Self::DEFAULT
2324 }
2325}
2326#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2327#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2328#[cfg_attr(feature = "serde", serde(tag = "type"))]
2329#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2330#[repr(u32)]
2331#[doc = "A data stream is not a fixed set of messages, but rather a recommendation to the autopilot software. Individual autopilots may or may not obey the recommended messages."]
2332pub enum MavDataStream {
2333 #[doc = "Enable all data streams"]
2334 MAV_DATA_STREAM_ALL = 0,
2335 #[doc = "Enable IMU_RAW, GPS_RAW, GPS_STATUS packets."]
2336 MAV_DATA_STREAM_RAW_SENSORS = 1,
2337 #[doc = "Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS"]
2338 MAV_DATA_STREAM_EXTENDED_STATUS = 2,
2339 #[doc = "Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW"]
2340 MAV_DATA_STREAM_RC_CHANNELS = 3,
2341 #[doc = "Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT."]
2342 MAV_DATA_STREAM_RAW_CONTROLLER = 4,
2343 #[doc = "Enable LOCAL_POSITION, GLOBAL_POSITION_INT messages."]
2344 MAV_DATA_STREAM_POSITION = 6,
2345 #[doc = "Dependent on the autopilot"]
2346 MAV_DATA_STREAM_EXTRA1 = 10,
2347 #[doc = "Dependent on the autopilot"]
2348 MAV_DATA_STREAM_EXTRA2 = 11,
2349 #[doc = "Dependent on the autopilot"]
2350 MAV_DATA_STREAM_EXTRA3 = 12,
2351}
2352impl MavDataStream {
2353 pub const DEFAULT: Self = Self::MAV_DATA_STREAM_ALL;
2354}
2355impl Default for MavDataStream {
2356 fn default() -> Self {
2357 Self::DEFAULT
2358 }
2359}
2360#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2361#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2362#[cfg_attr(feature = "serde", serde(tag = "type"))]
2363#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2364#[repr(u32)]
2365pub enum MavOdidHeightRef {
2366 #[doc = "The height field is relative to the take-off location."]
2367 MAV_ODID_HEIGHT_REF_OVER_TAKEOFF = 0,
2368 #[doc = "The height field is relative to ground."]
2369 MAV_ODID_HEIGHT_REF_OVER_GROUND = 1,
2370}
2371impl MavOdidHeightRef {
2372 pub const DEFAULT: Self = Self::MAV_ODID_HEIGHT_REF_OVER_TAKEOFF;
2373}
2374impl Default for MavOdidHeightRef {
2375 fn default() -> Self {
2376 Self::DEFAULT
2377 }
2378}
2379bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags used in HIL_ACTUATOR_CONTROLS message."] pub struct HilActuatorControlsFlags : u64 { # [doc = "Simulation is using lockstep"] const HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP = 1 ; } }
2380impl HilActuatorControlsFlags {
2381 pub const DEFAULT: Self = Self::HIL_ACTUATOR_CONTROLS_FLAGS_LOCKSTEP;
2382}
2383impl Default for HilActuatorControlsFlags {
2384 fn default() -> Self {
2385 Self::DEFAULT
2386 }
2387}
2388bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b00000000 indicates that none of the setpoint dimensions should be ignored."] pub struct AttitudeTargetTypemask : u8 { # [doc = "Ignore body roll rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE = 1 ; # [doc = "Ignore body pitch rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_PITCH_RATE_IGNORE = 2 ; # [doc = "Ignore body yaw rate"] const ATTITUDE_TARGET_TYPEMASK_BODY_YAW_RATE_IGNORE = 4 ; # [doc = "Use 3D body thrust setpoint instead of throttle"] const ATTITUDE_TARGET_TYPEMASK_THRUST_BODY_SET = 32 ; # [doc = "Ignore throttle"] const ATTITUDE_TARGET_TYPEMASK_THROTTLE_IGNORE = 64 ; # [doc = "Ignore attitude"] const ATTITUDE_TARGET_TYPEMASK_ATTITUDE_IGNORE = 128 ; } }
2389impl AttitudeTargetTypemask {
2390 pub const DEFAULT: Self = Self::ATTITUDE_TARGET_TYPEMASK_BODY_ROLL_RATE_IGNORE;
2391}
2392impl Default for AttitudeTargetTypemask {
2393 fn default() -> Self {
2394 Self::DEFAULT
2395 }
2396}
2397#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2398#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2399#[cfg_attr(feature = "serde", serde(tag = "type"))]
2400#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2401#[repr(u32)]
2402#[doc = "Focus types for MAV_CMD_SET_CAMERA_FOCUS"]
2403pub enum SetFocusType {
2404 #[doc = "Focus one step increment (-1 for focusing in, 1 for focusing out towards infinity)."]
2405 FOCUS_TYPE_STEP = 0,
2406 #[doc = "Continuous normalized focus in/out rate until stopped. Range -1..1, negative: in, positive: out towards infinity, 0 to stop focusing. Other values should be clipped to the range."]
2407 FOCUS_TYPE_CONTINUOUS = 1,
2408 #[doc = "Focus value as proportion of full camera focus range (a value between 0.0 and 100.0)"]
2409 FOCUS_TYPE_RANGE = 2,
2410 #[doc = "Focus value in metres. Note that there is no message to get the valid focus range of the camera, so this can type can only be used for cameras where the range is known (implying that this cannot reliably be used in a GCS for an arbitrary camera)."]
2411 FOCUS_TYPE_METERS = 3,
2412 #[doc = "Focus automatically."]
2413 FOCUS_TYPE_AUTO = 4,
2414 #[doc = "Single auto focus. Mainly used for still pictures. Usually abbreviated as AF-S."]
2415 FOCUS_TYPE_AUTO_SINGLE = 5,
2416 #[doc = "Continuous auto focus. Mainly used for dynamic scenes. Abbreviated as AF-C."]
2417 FOCUS_TYPE_AUTO_CONTINUOUS = 6,
2418}
2419impl SetFocusType {
2420 pub const DEFAULT: Self = Self::FOCUS_TYPE_STEP;
2421}
2422impl Default for SetFocusType {
2423 fn default() -> Self {
2424 Self::DEFAULT
2425 }
2426}
2427#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2428#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2429#[cfg_attr(feature = "serde", serde(tag = "type"))]
2430#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2431#[repr(u32)]
2432pub enum MavTunnelPayloadType {
2433 #[doc = "Encoding of payload unknown."]
2434 MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN = 0,
2435 #[doc = "Registered for STorM32 gimbal controller."]
2436 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED0 = 200,
2437 #[doc = "Registered for STorM32 gimbal controller."]
2438 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED1 = 201,
2439 #[doc = "Registered for STorM32 gimbal controller."]
2440 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED2 = 202,
2441 #[doc = "Registered for STorM32 gimbal controller."]
2442 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED3 = 203,
2443 #[doc = "Registered for STorM32 gimbal controller."]
2444 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED4 = 204,
2445 #[doc = "Registered for STorM32 gimbal controller."]
2446 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED5 = 205,
2447 #[doc = "Registered for STorM32 gimbal controller."]
2448 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED6 = 206,
2449 #[doc = "Registered for STorM32 gimbal controller."]
2450 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED7 = 207,
2451 #[doc = "Registered for STorM32 gimbal controller."]
2452 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED8 = 208,
2453 #[doc = "Registered for STorM32 gimbal controller."]
2454 MAV_TUNNEL_PAYLOAD_TYPE_STORM32_RESERVED9 = 209,
2455 #[doc = "Registered for ModalAI remote OSD protocol."]
2456 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_REMOTE_OSD = 210,
2457 #[doc = "Registered for ModalAI ESC UART passthru protocol."]
2458 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_ESC_UART_PASSTHRU = 211,
2459 #[doc = "Registered for ModalAI vendor use."]
2460 MAV_TUNNEL_PAYLOAD_TYPE_MODALAI_IO_UART_PASSTHRU = 212,
2461}
2462impl MavTunnelPayloadType {
2463 pub const DEFAULT: Self = Self::MAV_TUNNEL_PAYLOAD_TYPE_UNKNOWN;
2464}
2465impl Default for MavTunnelPayloadType {
2466 fn default() -> Self {
2467 Self::DEFAULT
2468 }
2469}
2470bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for X-Bit and reserved fields."] pub struct UavionixAdsbXbit : u8 { const UAVIONIX_ADSB_XBIT_ENABLED = 128 ; } }
2471impl UavionixAdsbXbit {
2472 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_XBIT_ENABLED;
2473}
2474impl Default for UavionixAdsbXbit {
2475 fn default() -> Self {
2476 Self::DEFAULT
2477 }
2478}
2479bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report failure cases over the high latency telemetry."] pub struct HlFailureFlag : u16 { # [doc = "GPS failure."] const HL_FAILURE_FLAG_GPS = 1 ; # [doc = "Differential pressure sensor failure."] const HL_FAILURE_FLAG_DIFFERENTIAL_PRESSURE = 2 ; # [doc = "Absolute pressure sensor failure."] const HL_FAILURE_FLAG_ABSOLUTE_PRESSURE = 4 ; # [doc = "Accelerometer sensor failure."] const HL_FAILURE_FLAG_3D_ACCEL = 8 ; # [doc = "Gyroscope sensor failure."] const HL_FAILURE_FLAG_3D_GYRO = 16 ; # [doc = "Magnetometer sensor failure."] const HL_FAILURE_FLAG_3D_MAG = 32 ; # [doc = "Terrain subsystem failure."] const HL_FAILURE_FLAG_TERRAIN = 64 ; # [doc = "Battery failure/critical low battery."] const HL_FAILURE_FLAG_BATTERY = 128 ; # [doc = "RC receiver failure/no RC connection."] const HL_FAILURE_FLAG_RC_RECEIVER = 256 ; # [doc = "Offboard link failure."] const HL_FAILURE_FLAG_OFFBOARD_LINK = 512 ; # [doc = "Engine failure."] const HL_FAILURE_FLAG_ENGINE = 1024 ; # [doc = "Geofence violation."] const HL_FAILURE_FLAG_GEOFENCE = 2048 ; # [doc = "Estimator failure, for example measurement rejection or large variances."] const HL_FAILURE_FLAG_ESTIMATOR = 4096 ; # [doc = "Mission failure."] const HL_FAILURE_FLAG_MISSION = 8192 ; } }
2480impl HlFailureFlag {
2481 pub const DEFAULT: Self = Self::HL_FAILURE_FLAG_GPS;
2482}
2483impl Default for HlFailureFlag {
2484 fn default() -> Self {
2485 Self::DEFAULT
2486 }
2487}
2488bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags are used in the AIS_VESSEL.fields bitmask to indicate validity of data in the other message fields. When set, the data is valid."] pub struct AisFlags : u16 { # [doc = "1 = Position accuracy less than 10m, 0 = position accuracy greater than 10m."] const AIS_FLAGS_POSITION_ACCURACY = 1 ; const AIS_FLAGS_VALID_COG = 2 ; const AIS_FLAGS_VALID_VELOCITY = 4 ; # [doc = "1 = Velocity over 52.5765m/s (102.2 knots)"] const AIS_FLAGS_HIGH_VELOCITY = 8 ; const AIS_FLAGS_VALID_TURN_RATE = 16 ; # [doc = "Only the sign of the returned turn rate value is valid, either greater than 5deg/30s or less than -5deg/30s"] const AIS_FLAGS_TURN_RATE_SIGN_ONLY = 32 ; const AIS_FLAGS_VALID_DIMENSIONS = 64 ; # [doc = "Distance to bow is larger than 511m"] const AIS_FLAGS_LARGE_BOW_DIMENSION = 128 ; # [doc = "Distance to stern is larger than 511m"] const AIS_FLAGS_LARGE_STERN_DIMENSION = 256 ; # [doc = "Distance to port side is larger than 63m"] const AIS_FLAGS_LARGE_PORT_DIMENSION = 512 ; # [doc = "Distance to starboard side is larger than 63m"] const AIS_FLAGS_LARGE_STARBOARD_DIMENSION = 1024 ; const AIS_FLAGS_VALID_CALLSIGN = 2048 ; const AIS_FLAGS_VALID_NAME = 4096 ; } }
2489impl AisFlags {
2490 pub const DEFAULT: Self = Self::AIS_FLAGS_POSITION_ACCURACY;
2491}
2492impl Default for AisFlags {
2493 fn default() -> Self {
2494 Self::DEFAULT
2495 }
2496}
2497#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2498#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2499#[cfg_attr(feature = "serde", serde(tag = "type"))]
2500#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2501#[repr(u32)]
2502#[doc = "Modes of illuminator"]
2503pub enum IlluminatorMode {
2504 #[doc = "Illuminator mode is not specified/unknown"]
2505 ILLUMINATOR_MODE_UNKNOWN = 0,
2506 #[doc = "Illuminator behavior is controlled by MAV_CMD_DO_ILLUMINATOR_CONFIGURE settings"]
2507 ILLUMINATOR_MODE_INTERNAL_CONTROL = 1,
2508 #[doc = "Illuminator behavior is controlled by external factors: e.g. an external hardware signal"]
2509 ILLUMINATOR_MODE_EXTERNAL_SYNC = 2,
2510}
2511impl IlluminatorMode {
2512 pub const DEFAULT: Self = Self::ILLUMINATOR_MODE_UNKNOWN;
2513}
2514impl Default for IlluminatorMode {
2515 fn default() -> Self {
2516 Self::DEFAULT
2517 }
2518}
2519#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2520#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2521#[cfg_attr(feature = "serde", serde(tag = "type"))]
2522#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2523#[repr(u32)]
2524#[doc = "Type of mission items being requested/sent in mission protocol."]
2525pub enum MavMissionType {
2526 #[doc = "Items are mission commands for main mission."]
2527 MAV_MISSION_TYPE_MISSION = 0,
2528 #[doc = "Specifies GeoFence area(s). Items are MAV_CMD_NAV_FENCE_ GeoFence items."]
2529 MAV_MISSION_TYPE_FENCE = 1,
2530 #[doc = "Specifies the rally points for the vehicle. Rally points are alternative RTL points. Items are MAV_CMD_NAV_RALLY_POINT rally point items."]
2531 MAV_MISSION_TYPE_RALLY = 2,
2532 #[doc = "Only used in MISSION_CLEAR_ALL to clear all mission types."]
2533 MAV_MISSION_TYPE_ALL = 255,
2534}
2535impl MavMissionType {
2536 pub const DEFAULT: Self = Self::MAV_MISSION_TYPE_MISSION;
2537}
2538impl Default for MavMissionType {
2539 fn default() -> Self {
2540 Self::DEFAULT
2541 }
2542}
2543#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2544#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2545#[cfg_attr(feature = "serde", serde(tag = "type"))]
2546#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2547#[repr(u32)]
2548#[doc = "Possible actions an aircraft can take to avoid a collision."]
2549pub enum MavCollisionAction {
2550 #[doc = "Ignore any potential collisions"]
2551 MAV_COLLISION_ACTION_NONE = 0,
2552 #[doc = "Report potential collision"]
2553 MAV_COLLISION_ACTION_REPORT = 1,
2554 #[doc = "Ascend or Descend to avoid threat"]
2555 MAV_COLLISION_ACTION_ASCEND_OR_DESCEND = 2,
2556 #[doc = "Move horizontally to avoid threat"]
2557 MAV_COLLISION_ACTION_MOVE_HORIZONTALLY = 3,
2558 #[doc = "Aircraft to move perpendicular to the collision's velocity vector"]
2559 MAV_COLLISION_ACTION_MOVE_PERPENDICULAR = 4,
2560 #[doc = "Aircraft to fly directly back to its launch point"]
2561 MAV_COLLISION_ACTION_RTL = 5,
2562 #[doc = "Aircraft to stop in place"]
2563 MAV_COLLISION_ACTION_HOVER = 6,
2564}
2565impl MavCollisionAction {
2566 pub const DEFAULT: Self = Self::MAV_COLLISION_ACTION_NONE;
2567}
2568impl Default for MavCollisionAction {
2569 fn default() -> Self {
2570 Self::DEFAULT
2571 }
2572}
2573bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Transceiver RF control flags for ADS-B transponder dynamic reports"] pub struct UavionixAdsbOutRfSelect : u8 { const UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED = 1 ; const UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED = 2 ; } }
2574impl UavionixAdsbOutRfSelect {
2575 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_RF_SELECT_RX_ENABLED;
2576}
2577impl Default for UavionixAdsbOutRfSelect {
2578 fn default() -> Self {
2579 Self::DEFAULT
2580 }
2581}
2582bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder status report"] pub struct UavionixAdsbOutStatusState : u8 { const UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND = 1 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_INTERROGATED_SINCE_LAST = 2 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_XBIT_ENABLED = 4 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_IDENT_ACTIVE = 8 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_A_ENABLED = 16 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_C_ENABLED = 32 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_MODE_S_ENABLED = 64 ; const UAVIONIX_ADSB_OUT_STATUS_STATE_1090ES_TX_ENABLED = 128 ; } }
2583impl UavionixAdsbOutStatusState {
2584 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_STATUS_STATE_ON_GROUND;
2585}
2586impl Default for UavionixAdsbOutStatusState {
2587 fn default() -> Self {
2588 Self::DEFAULT
2589 }
2590}
2591#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2592#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2593#[cfg_attr(feature = "serde", serde(tag = "type"))]
2594#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2595#[repr(u32)]
2596#[doc = "MAV FTP opcodes: <https://mavlink.io/en/services/ftp.html>"]
2597pub enum MavFtpOpcode {
2598 #[doc = "None. Ignored, always ACKed"]
2599 MAV_FTP_OPCODE_NONE = 0,
2600 #[doc = "TerminateSession: Terminates open Read session"]
2601 MAV_FTP_OPCODE_TERMINATESESSION = 1,
2602 #[doc = "ResetSessions: Terminates all open read sessions"]
2603 MAV_FTP_OPCODE_RESETSESSION = 2,
2604 #[doc = "ListDirectory. List files and directories in path from offset"]
2605 MAV_FTP_OPCODE_LISTDIRECTORY = 3,
2606 #[doc = "OpenFileRO: Opens file at path for reading, returns session"]
2607 MAV_FTP_OPCODE_OPENFILERO = 4,
2608 #[doc = "ReadFile: Reads size bytes from offset in session"]
2609 MAV_FTP_OPCODE_READFILE = 5,
2610 #[doc = "CreateFile: Creates file at path for writing, returns session"]
2611 MAV_FTP_OPCODE_CREATEFILE = 6,
2612 #[doc = "WriteFile: Writes size bytes to offset in session"]
2613 MAV_FTP_OPCODE_WRITEFILE = 7,
2614 #[doc = "RemoveFile: Remove file at path"]
2615 MAV_FTP_OPCODE_REMOVEFILE = 8,
2616 #[doc = "CreateDirectory: Creates directory at path"]
2617 MAV_FTP_OPCODE_CREATEDIRECTORY = 9,
2618 #[doc = "RemoveDirectory: Removes directory at path. The directory must be empty."]
2619 MAV_FTP_OPCODE_REMOVEDIRECTORY = 10,
2620 #[doc = "OpenFileWO: Opens file at path for writing, returns session"]
2621 MAV_FTP_OPCODE_OPENFILEWO = 11,
2622 #[doc = "TruncateFile: Truncate file at path to offset length"]
2623 MAV_FTP_OPCODE_TRUNCATEFILE = 12,
2624 #[doc = "Rename: Rename path1 to path2"]
2625 MAV_FTP_OPCODE_RENAME = 13,
2626 #[doc = "CalcFileCRC32: Calculate CRC32 for file at path"]
2627 MAV_FTP_OPCODE_CALCFILECRC = 14,
2628 #[doc = "BurstReadFile: Burst download session file"]
2629 MAV_FTP_OPCODE_BURSTREADFILE = 15,
2630 #[doc = "ACK: ACK response"]
2631 MAV_FTP_OPCODE_ACK = 128,
2632 #[doc = "NAK: NAK response"]
2633 MAV_FTP_OPCODE_NAK = 129,
2634}
2635impl MavFtpOpcode {
2636 pub const DEFAULT: Self = Self::MAV_FTP_OPCODE_NONE;
2637}
2638impl Default for MavFtpOpcode {
2639 fn default() -> Self {
2640 Self::DEFAULT
2641 }
2642}
2643#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2644#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2645#[cfg_attr(feature = "serde", serde(tag = "type"))]
2646#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2647#[repr(u32)]
2648pub enum MavOdidUaType {
2649 #[doc = "No UA (Unmanned Aircraft) type defined."]
2650 MAV_ODID_UA_TYPE_NONE = 0,
2651 #[doc = "Aeroplane/Airplane. Fixed wing."]
2652 MAV_ODID_UA_TYPE_AEROPLANE = 1,
2653 #[doc = "Helicopter or multirotor."]
2654 MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR = 2,
2655 #[doc = "Gyroplane."]
2656 MAV_ODID_UA_TYPE_GYROPLANE = 3,
2657 #[doc = "VTOL (Vertical Take-Off and Landing). Fixed wing aircraft that can take off vertically."]
2658 MAV_ODID_UA_TYPE_HYBRID_LIFT = 4,
2659 #[doc = "Ornithopter."]
2660 MAV_ODID_UA_TYPE_ORNITHOPTER = 5,
2661 #[doc = "Glider."]
2662 MAV_ODID_UA_TYPE_GLIDER = 6,
2663 #[doc = "Kite."]
2664 MAV_ODID_UA_TYPE_KITE = 7,
2665 #[doc = "Free Balloon."]
2666 MAV_ODID_UA_TYPE_FREE_BALLOON = 8,
2667 #[doc = "Captive Balloon."]
2668 MAV_ODID_UA_TYPE_CAPTIVE_BALLOON = 9,
2669 #[doc = "Airship. E.g. a blimp."]
2670 MAV_ODID_UA_TYPE_AIRSHIP = 10,
2671 #[doc = "Free Fall/Parachute (unpowered)."]
2672 MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE = 11,
2673 #[doc = "Rocket."]
2674 MAV_ODID_UA_TYPE_ROCKET = 12,
2675 #[doc = "Tethered powered aircraft."]
2676 MAV_ODID_UA_TYPE_TETHERED_POWERED_AIRCRAFT = 13,
2677 #[doc = "Ground Obstacle."]
2678 MAV_ODID_UA_TYPE_GROUND_OBSTACLE = 14,
2679 #[doc = "Other type of aircraft not listed earlier."]
2680 MAV_ODID_UA_TYPE_OTHER = 15,
2681}
2682impl MavOdidUaType {
2683 pub const DEFAULT: Self = Self::MAV_ODID_UA_TYPE_NONE;
2684}
2685impl Default for MavOdidUaType {
2686 fn default() -> Self {
2687 Self::DEFAULT
2688 }
2689}
2690bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Power supply status flags (bitmask)"] pub struct MavPowerStatus : u16 { # [doc = "main brick power supply valid"] const MAV_POWER_STATUS_BRICK_VALID = 1 ; # [doc = "main servo power supply valid for FMU"] const MAV_POWER_STATUS_SERVO_VALID = 2 ; # [doc = "USB power is connected"] const MAV_POWER_STATUS_USB_CONNECTED = 4 ; # [doc = "peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_OVERCURRENT = 8 ; # [doc = "hi-power peripheral supply is in over-current state"] const MAV_POWER_STATUS_PERIPH_HIPOWER_OVERCURRENT = 16 ; # [doc = "Power status has changed since boot"] const MAV_POWER_STATUS_CHANGED = 32 ; } }
2691impl MavPowerStatus {
2692 pub const DEFAULT: Self = Self::MAV_POWER_STATUS_BRICK_VALID;
2693}
2694impl Default for MavPowerStatus {
2695 fn default() -> Self {
2696 Self::DEFAULT
2697 }
2698}
2699#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2700#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2701#[cfg_attr(feature = "serde", serde(tag = "type"))]
2702#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2703#[repr(u32)]
2704#[doc = "Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: <http://www.kiwisyslog.com/kb/info:-syslog-message-levels/>."]
2705pub enum MavSeverity {
2706 #[doc = "System is unusable. This is a \"panic\" condition."]
2707 MAV_SEVERITY_EMERGENCY = 0,
2708 #[doc = "Action should be taken immediately. Indicates error in non-critical systems."]
2709 MAV_SEVERITY_ALERT = 1,
2710 #[doc = "Action must be taken immediately. Indicates failure in a primary system."]
2711 MAV_SEVERITY_CRITICAL = 2,
2712 #[doc = "Indicates an error in secondary/redundant systems."]
2713 MAV_SEVERITY_ERROR = 3,
2714 #[doc = "Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning."]
2715 MAV_SEVERITY_WARNING = 4,
2716 #[doc = "An unusual event has occurred, though not an error condition. This should be investigated for the root cause."]
2717 MAV_SEVERITY_NOTICE = 5,
2718 #[doc = "Normal operational messages. Useful for logging. No action is required for these messages."]
2719 MAV_SEVERITY_INFO = 6,
2720 #[doc = "Useful non-operational messages that can assist in debugging. These should not occur during normal operation."]
2721 MAV_SEVERITY_DEBUG = 7,
2722}
2723impl MavSeverity {
2724 pub const DEFAULT: Self = Self::MAV_SEVERITY_EMERGENCY;
2725}
2726impl Default for MavSeverity {
2727 fn default() -> Self {
2728 Self::DEFAULT
2729 }
2730}
2731#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2732#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2733#[cfg_attr(feature = "serde", serde(tag = "type"))]
2734#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2735#[repr(u32)]
2736#[doc = "Micro air vehicle / autopilot classes. This identifies the individual model."]
2737pub enum MavAutopilot {
2738 #[doc = "Generic autopilot, full support for everything"]
2739 MAV_AUTOPILOT_GENERIC = 0,
2740 #[doc = "Reserved for future use."]
2741 MAV_AUTOPILOT_RESERVED = 1,
2742 #[doc = "SLUGS autopilot, <http://slugsuav.soe.ucsc.edu>"]
2743 MAV_AUTOPILOT_SLUGS = 2,
2744 #[doc = "ArduPilot - Plane/Copter/Rover/Sub/Tracker, <https://ardupilot.org>"]
2745 MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
2746 #[doc = "OpenPilot, <http://openpilot.org>"]
2747 MAV_AUTOPILOT_OPENPILOT = 4,
2748 #[doc = "Generic autopilot only supporting simple waypoints"]
2749 MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY = 5,
2750 #[doc = "Generic autopilot supporting waypoints and other simple navigation commands"]
2751 MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY = 6,
2752 #[doc = "Generic autopilot supporting the full mission command set"]
2753 MAV_AUTOPILOT_GENERIC_MISSION_FULL = 7,
2754 #[doc = "No valid autopilot, e.g. a GCS or other MAVLink component"]
2755 MAV_AUTOPILOT_INVALID = 8,
2756 #[doc = "PPZ UAV - <http://nongnu.org/paparazzi>"]
2757 MAV_AUTOPILOT_PPZ = 9,
2758 #[doc = "UAV Dev Board"]
2759 MAV_AUTOPILOT_UDB = 10,
2760 #[doc = "FlexiPilot"]
2761 MAV_AUTOPILOT_FP = 11,
2762 #[doc = "PX4 Autopilot - <http://px4.io/>"]
2763 MAV_AUTOPILOT_PX4 = 12,
2764 #[doc = "SMACCMPilot - <http://smaccmpilot.org>"]
2765 MAV_AUTOPILOT_SMACCMPILOT = 13,
2766 #[doc = "AutoQuad -- <http://autoquad.org>"]
2767 MAV_AUTOPILOT_AUTOQUAD = 14,
2768 #[doc = "Armazila -- <http://armazila.com>"]
2769 MAV_AUTOPILOT_ARMAZILA = 15,
2770 #[doc = "Aerob -- <http://aerob.ru>"]
2771 MAV_AUTOPILOT_AEROB = 16,
2772 #[doc = "ASLUAV autopilot -- <http://www.asl.ethz.ch>"]
2773 MAV_AUTOPILOT_ASLUAV = 17,
2774 #[doc = "SmartAP Autopilot - <http://sky-drones.com>"]
2775 MAV_AUTOPILOT_SMARTAP = 18,
2776 #[doc = "AirRails - <http://uaventure.com>"]
2777 MAV_AUTOPILOT_AIRRAILS = 19,
2778 #[doc = "Fusion Reflex - <https://fusion.engineering>"]
2779 MAV_AUTOPILOT_REFLEX = 20,
2780}
2781impl MavAutopilot {
2782 pub const DEFAULT: Self = Self::MAV_AUTOPILOT_GENERIC;
2783}
2784impl Default for MavAutopilot {
2785 fn default() -> Self {
2786 Self::DEFAULT
2787 }
2788}
2789#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2790#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2791#[cfg_attr(feature = "serde", serde(tag = "type"))]
2792#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2793#[repr(u32)]
2794#[doc = "Parachute actions. Trigger release and enable/disable auto-release."]
2795pub enum ParachuteAction {
2796 #[doc = "Disable auto-release of parachute (i.e. release triggered by crash detectors)."]
2797 PARACHUTE_DISABLE = 0,
2798 #[doc = "Enable auto-release of parachute."]
2799 PARACHUTE_ENABLE = 1,
2800 #[doc = "Release parachute and kill motors."]
2801 PARACHUTE_RELEASE = 2,
2802}
2803impl ParachuteAction {
2804 pub const DEFAULT: Self = Self::PARACHUTE_DISABLE;
2805}
2806impl Default for ParachuteAction {
2807 fn default() -> Self {
2808 Self::DEFAULT
2809 }
2810}
2811#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2812#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2813#[cfg_attr(feature = "serde", serde(tag = "type"))]
2814#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2815#[repr(u32)]
2816#[doc = "State flags for ADS-B transponder status report"]
2817pub enum UavionixAdsbOutStatusNicNacp {
2818 UAVIONIX_ADSB_NIC_CR_20_NM = 1,
2819 UAVIONIX_ADSB_NIC_CR_8_NM = 2,
2820 UAVIONIX_ADSB_NIC_CR_4_NM = 3,
2821 UAVIONIX_ADSB_NIC_CR_2_NM = 4,
2822 UAVIONIX_ADSB_NIC_CR_1_NM = 5,
2823 UAVIONIX_ADSB_NIC_CR_0_3_NM = 6,
2824 UAVIONIX_ADSB_NIC_CR_0_2_NM = 7,
2825 UAVIONIX_ADSB_NIC_CR_0_1_NM = 8,
2826 UAVIONIX_ADSB_NIC_CR_75_M = 9,
2827 UAVIONIX_ADSB_NIC_CR_25_M = 10,
2828 UAVIONIX_ADSB_NIC_CR_7_5_M = 11,
2829 UAVIONIX_ADSB_NACP_EPU_10_NM = 16,
2830 UAVIONIX_ADSB_NACP_EPU_4_NM = 32,
2831 UAVIONIX_ADSB_NACP_EPU_2_NM = 48,
2832 UAVIONIX_ADSB_NACP_EPU_1_NM = 64,
2833 UAVIONIX_ADSB_NACP_EPU_0_5_NM = 80,
2834 UAVIONIX_ADSB_NACP_EPU_0_3_NM = 96,
2835 UAVIONIX_ADSB_NACP_EPU_0_1_NM = 112,
2836 UAVIONIX_ADSB_NACP_EPU_0_05_NM = 128,
2837 UAVIONIX_ADSB_NACP_EPU_30_M = 144,
2838 UAVIONIX_ADSB_NACP_EPU_10_M = 160,
2839 UAVIONIX_ADSB_NACP_EPU_3_M = 176,
2840}
2841impl UavionixAdsbOutStatusNicNacp {
2842 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_NIC_CR_20_NM;
2843}
2844impl Default for UavionixAdsbOutStatusNicNacp {
2845 fn default() -> Self {
2846 Self::DEFAULT
2847 }
2848}
2849#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2850#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2851#[cfg_attr(feature = "serde", serde(tag = "type"))]
2852#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2853#[repr(u32)]
2854#[doc = "RTK GPS baseline coordinate system, used for RTK corrections"]
2855pub enum RtkBaselineCoordinateSystem {
2856 #[doc = "Earth-centered, Earth-fixed"]
2857 RTK_BASELINE_COORDINATE_SYSTEM_ECEF = 0,
2858 #[doc = "RTK basestation centered, north, east, down"]
2859 RTK_BASELINE_COORDINATE_SYSTEM_NED = 1,
2860}
2861impl RtkBaselineCoordinateSystem {
2862 pub const DEFAULT: Self = Self::RTK_BASELINE_COORDINATE_SYSTEM_ECEF;
2863}
2864impl Default for RtkBaselineCoordinateSystem {
2865 fn default() -> Self {
2866 Self::DEFAULT
2867 }
2868}
2869#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2870#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2871#[cfg_attr(feature = "serde", serde(tag = "type"))]
2872#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2873#[repr(u32)]
2874pub enum MavOdidVerAcc {
2875 #[doc = "The vertical accuracy is unknown."]
2876 MAV_ODID_VER_ACC_UNKNOWN = 0,
2877 #[doc = "The vertical accuracy is smaller than 150 meter."]
2878 MAV_ODID_VER_ACC_150_METER = 1,
2879 #[doc = "The vertical accuracy is smaller than 45 meter."]
2880 MAV_ODID_VER_ACC_45_METER = 2,
2881 #[doc = "The vertical accuracy is smaller than 25 meter."]
2882 MAV_ODID_VER_ACC_25_METER = 3,
2883 #[doc = "The vertical accuracy is smaller than 10 meter."]
2884 MAV_ODID_VER_ACC_10_METER = 4,
2885 #[doc = "The vertical accuracy is smaller than 3 meter."]
2886 MAV_ODID_VER_ACC_3_METER = 5,
2887 #[doc = "The vertical accuracy is smaller than 1 meter."]
2888 MAV_ODID_VER_ACC_1_METER = 6,
2889}
2890impl MavOdidVerAcc {
2891 pub const DEFAULT: Self = Self::MAV_ODID_VER_ACC_UNKNOWN;
2892}
2893impl Default for MavOdidVerAcc {
2894 fn default() -> Self {
2895 Self::DEFAULT
2896 }
2897}
2898#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2899#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2900#[cfg_attr(feature = "serde", serde(tag = "type"))]
2901#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2902#[repr(u32)]
2903pub enum MavOdidDescType {
2904 #[doc = "Optional free-form text description of the purpose of the flight."]
2905 MAV_ODID_DESC_TYPE_TEXT = 0,
2906 #[doc = "Optional additional clarification when status == MAV_ODID_STATUS_EMERGENCY."]
2907 MAV_ODID_DESC_TYPE_EMERGENCY = 1,
2908 #[doc = "Optional additional clarification when status != MAV_ODID_STATUS_EMERGENCY."]
2909 MAV_ODID_DESC_TYPE_EXTENDED_STATUS = 2,
2910}
2911impl MavOdidDescType {
2912 pub const DEFAULT: Self = Self::MAV_ODID_DESC_TYPE_TEXT;
2913}
2914impl Default for MavOdidDescType {
2915 fn default() -> Self {
2916 Self::DEFAULT
2917 }
2918}
2919#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2920#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2921#[cfg_attr(feature = "serde", serde(tag = "type"))]
2922#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2923#[repr(u32)]
2924pub enum MavOdidTimeAcc {
2925 #[doc = "The timestamp accuracy is unknown."]
2926 MAV_ODID_TIME_ACC_UNKNOWN = 0,
2927 #[doc = "The timestamp accuracy is smaller than or equal to 0.1 second."]
2928 MAV_ODID_TIME_ACC_0_1_SECOND = 1,
2929 #[doc = "The timestamp accuracy is smaller than or equal to 0.2 second."]
2930 MAV_ODID_TIME_ACC_0_2_SECOND = 2,
2931 #[doc = "The timestamp accuracy is smaller than or equal to 0.3 second."]
2932 MAV_ODID_TIME_ACC_0_3_SECOND = 3,
2933 #[doc = "The timestamp accuracy is smaller than or equal to 0.4 second."]
2934 MAV_ODID_TIME_ACC_0_4_SECOND = 4,
2935 #[doc = "The timestamp accuracy is smaller than or equal to 0.5 second."]
2936 MAV_ODID_TIME_ACC_0_5_SECOND = 5,
2937 #[doc = "The timestamp accuracy is smaller than or equal to 0.6 second."]
2938 MAV_ODID_TIME_ACC_0_6_SECOND = 6,
2939 #[doc = "The timestamp accuracy is smaller than or equal to 0.7 second."]
2940 MAV_ODID_TIME_ACC_0_7_SECOND = 7,
2941 #[doc = "The timestamp accuracy is smaller than or equal to 0.8 second."]
2942 MAV_ODID_TIME_ACC_0_8_SECOND = 8,
2943 #[doc = "The timestamp accuracy is smaller than or equal to 0.9 second."]
2944 MAV_ODID_TIME_ACC_0_9_SECOND = 9,
2945 #[doc = "The timestamp accuracy is smaller than or equal to 1.0 second."]
2946 MAV_ODID_TIME_ACC_1_0_SECOND = 10,
2947 #[doc = "The timestamp accuracy is smaller than or equal to 1.1 second."]
2948 MAV_ODID_TIME_ACC_1_1_SECOND = 11,
2949 #[doc = "The timestamp accuracy is smaller than or equal to 1.2 second."]
2950 MAV_ODID_TIME_ACC_1_2_SECOND = 12,
2951 #[doc = "The timestamp accuracy is smaller than or equal to 1.3 second."]
2952 MAV_ODID_TIME_ACC_1_3_SECOND = 13,
2953 #[doc = "The timestamp accuracy is smaller than or equal to 1.4 second."]
2954 MAV_ODID_TIME_ACC_1_4_SECOND = 14,
2955 #[doc = "The timestamp accuracy is smaller than or equal to 1.5 second."]
2956 MAV_ODID_TIME_ACC_1_5_SECOND = 15,
2957}
2958impl MavOdidTimeAcc {
2959 pub const DEFAULT: Self = Self::MAV_ODID_TIME_ACC_UNKNOWN;
2960}
2961impl Default for MavOdidTimeAcc {
2962 fn default() -> Self {
2963 Self::DEFAULT
2964 }
2965}
2966bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera tracking target data (shows where tracked target is within image)"] pub struct CameraTrackingTargetData : u8 { # [doc = "Target data embedded in image data (proprietary)"] const CAMERA_TRACKING_TARGET_DATA_EMBEDDED = 1 ; # [doc = "Target data rendered in image"] const CAMERA_TRACKING_TARGET_DATA_RENDERED = 2 ; # [doc = "Target data within status message (Point or Rectangle)"] const CAMERA_TRACKING_TARGET_DATA_IN_STATUS = 4 ; } }
2967impl CameraTrackingTargetData {
2968 pub const DEFAULT: Self = Self::CAMERA_TRACKING_TARGET_DATA_EMBEDDED;
2969}
2970impl Default for CameraTrackingTargetData {
2971 fn default() -> Self {
2972 Self::DEFAULT
2973 }
2974}
2975#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2976#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2977#[cfg_attr(feature = "serde", serde(tag = "type"))]
2978#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
2979#[repr(u32)]
2980#[doc = "Axes that will be autotuned by MAV_CMD_DO_AUTOTUNE_ENABLE. Note that at least one flag must be set in MAV_CMD_DO_AUTOTUNE_ENABLE.param2: if none are set, the flight stack will tune its default set of axes."]
2981pub enum AutotuneAxis {
2982 #[doc = "Autotune roll axis."]
2983 AUTOTUNE_AXIS_ROLL = 1,
2984 #[doc = "Autotune pitch axis."]
2985 AUTOTUNE_AXIS_PITCH = 2,
2986 #[doc = "Autotune yaw axis."]
2987 AUTOTUNE_AXIS_YAW = 4,
2988}
2989impl AutotuneAxis {
2990 pub const DEFAULT: Self = Self::AUTOTUNE_AXIS_ROLL;
2991}
2992impl Default for AutotuneAxis {
2993 fn default() -> Self {
2994 Self::DEFAULT
2995 }
2996}
2997#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
2998#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
2999#[cfg_attr(feature = "serde", serde(tag = "type"))]
3000#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3001#[repr(u32)]
3002#[doc = "Airborne status of UAS."]
3003pub enum UtmFlightState {
3004 #[doc = "The flight state can't be determined."]
3005 UTM_FLIGHT_STATE_UNKNOWN = 1,
3006 #[doc = "UAS on ground."]
3007 UTM_FLIGHT_STATE_GROUND = 2,
3008 #[doc = "UAS airborne."]
3009 UTM_FLIGHT_STATE_AIRBORNE = 3,
3010 #[doc = "UAS is in an emergency flight state."]
3011 UTM_FLIGHT_STATE_EMERGENCY = 16,
3012 #[doc = "UAS has no active controls."]
3013 UTM_FLIGHT_STATE_NOCTRL = 32,
3014}
3015impl UtmFlightState {
3016 pub const DEFAULT: Self = Self::UTM_FLIGHT_STATE_UNKNOWN;
3017}
3018impl Default for UtmFlightState {
3019 fn default() -> Self {
3020 Self::DEFAULT
3021 }
3022}
3023bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These encode the sensors whose status is sent as part of the SYS_STATUS message in the extended fields."] pub struct MavSysStatusSensorExtended : u32 { # [doc = "0x01 Recovery system (parachute, balloon, retracts etc)"] const MAV_SYS_STATUS_RECOVERY_SYSTEM = 1 ; } }
3024impl MavSysStatusSensorExtended {
3025 pub const DEFAULT: Self = Self::MAV_SYS_STATUS_RECOVERY_SYSTEM;
3026}
3027impl Default for MavSysStatusSensorExtended {
3028 fn default() -> Self {
3029 Self::DEFAULT
3030 }
3031}
3032bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "These flags indicate status such as data validity of each data source. Set = data valid"] pub struct AdsbFlags : u16 { const ADSB_FLAGS_VALID_COORDS = 1 ; const ADSB_FLAGS_VALID_ALTITUDE = 2 ; const ADSB_FLAGS_VALID_HEADING = 4 ; const ADSB_FLAGS_VALID_VELOCITY = 8 ; const ADSB_FLAGS_VALID_CALLSIGN = 16 ; const ADSB_FLAGS_VALID_SQUAWK = 32 ; const ADSB_FLAGS_SIMULATED = 64 ; const ADSB_FLAGS_VERTICAL_VELOCITY_VALID = 128 ; const ADSB_FLAGS_BARO_VALID = 256 ; const ADSB_FLAGS_SOURCE_UAT = 32768 ; } }
3033impl AdsbFlags {
3034 pub const DEFAULT: Self = Self::ADSB_FLAGS_VALID_COORDS;
3035}
3036impl Default for AdsbFlags {
3037 fn default() -> Self {
3038 Self::DEFAULT
3039 }
3040}
3041bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Smart battery supply status/fault flags (bitmask) for health indication. The battery must also report either MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY if any of these are set."] pub struct MavBatteryFault : u32 { # [doc = "Battery has deep discharged."] const MAV_BATTERY_FAULT_DEEP_DISCHARGE = 1 ; # [doc = "Voltage spikes."] const MAV_BATTERY_FAULT_SPIKES = 2 ; # [doc = "One or more cells have failed. Battery should also report MAV_BATTERY_CHARGE_STATE_FAILE (and should not be used)."] const MAV_BATTERY_FAULT_CELL_FAIL = 4 ; # [doc = "Over-current fault."] const MAV_BATTERY_FAULT_OVER_CURRENT = 8 ; # [doc = "Over-temperature fault."] const MAV_BATTERY_FAULT_OVER_TEMPERATURE = 16 ; # [doc = "Under-temperature fault."] const MAV_BATTERY_FAULT_UNDER_TEMPERATURE = 32 ; # [doc = "Vehicle voltage is not compatible with this battery (batteries on same power rail should have similar voltage)."] const MAV_BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 64 ; # [doc = "Battery firmware is not compatible with current autopilot firmware."] const MAV_BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 128 ; # [doc = "Battery is not compatible due to cell configuration (e.g. 5s1p when vehicle requires 6s)."] const BATTERY_FAULT_INCOMPATIBLE_CELLS_CONFIGURATION = 256 ; } }
3042impl MavBatteryFault {
3043 pub const DEFAULT: Self = Self::MAV_BATTERY_FAULT_DEEP_DISCHARGE;
3044}
3045impl Default for MavBatteryFault {
3046 fn default() -> Self {
3047 Self::DEFAULT
3048 }
3049}
3050#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3051#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3052#[cfg_attr(feature = "serde", serde(tag = "type"))]
3053#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3054#[repr(u32)]
3055#[doc = "Bitmap of options for the MAV_CMD_DO_REPOSITION"]
3056pub enum MavDoRepositionFlags {
3057 #[doc = "The aircraft should immediately transition into guided. This should not be set for follow me applications"]
3058 MAV_DO_REPOSITION_FLAGS_CHANGE_MODE = 1,
3059}
3060impl MavDoRepositionFlags {
3061 pub const DEFAULT: Self = Self::MAV_DO_REPOSITION_FLAGS_CHANGE_MODE;
3062}
3063impl Default for MavDoRepositionFlags {
3064 fn default() -> Self {
3065 Self::DEFAULT
3066 }
3067}
3068bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags in the HIL_SENSOR message indicate which fields have updated since the last message"] pub struct HilSensorUpdatedFlags : u32 { # [doc = "The value in the xacc field has been updated"] const HIL_SENSOR_UPDATED_XACC = 1 ; # [doc = "The value in the yacc field has been updated"] const HIL_SENSOR_UPDATED_YACC = 2 ; # [doc = "The value in the zacc field has been updated"] const HIL_SENSOR_UPDATED_ZACC = 4 ; # [doc = "The value in the xgyro field has been updated"] const HIL_SENSOR_UPDATED_XGYRO = 8 ; # [doc = "The value in the ygyro field has been updated"] const HIL_SENSOR_UPDATED_YGYRO = 16 ; # [doc = "The value in the zgyro field has been updated"] const HIL_SENSOR_UPDATED_ZGYRO = 32 ; # [doc = "The value in the xmag field has been updated"] const HIL_SENSOR_UPDATED_XMAG = 64 ; # [doc = "The value in the ymag field has been updated"] const HIL_SENSOR_UPDATED_YMAG = 128 ; # [doc = "The value in the zmag field has been updated"] const HIL_SENSOR_UPDATED_ZMAG = 256 ; # [doc = "The value in the abs_pressure field has been updated"] const HIL_SENSOR_UPDATED_ABS_PRESSURE = 512 ; # [doc = "The value in the diff_pressure field has been updated"] const HIL_SENSOR_UPDATED_DIFF_PRESSURE = 1024 ; # [doc = "The value in the pressure_alt field has been updated"] const HIL_SENSOR_UPDATED_PRESSURE_ALT = 2048 ; # [doc = "The value in the temperature field has been updated"] const HIL_SENSOR_UPDATED_TEMPERATURE = 4096 ; # [doc = "Full reset of attitude/position/velocities/etc was performed in sim (Bit 31)."] const HIL_SENSOR_UPDATED_RESET = 2147483648 ; } }
3069impl HilSensorUpdatedFlags {
3070 pub const DEFAULT: Self = Self::HIL_SENSOR_UPDATED_XACC;
3071}
3072impl Default for HilSensorUpdatedFlags {
3073 fn default() -> Self {
3074 Self::DEFAULT
3075 }
3076}
3077bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for high level gimbal manager operation The first 16 bits are identical to the GIMBAL_DEVICE_FLAGS."] pub struct GimbalManagerFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_FLAGS_RETRACT."] const GIMBAL_MANAGER_FLAGS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_NEUTRAL."] const GIMBAL_MANAGER_FLAGS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ROLL_LOCK."] const GIMBAL_MANAGER_FLAGS_ROLL_LOCK = 4 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_PITCH_LOCK."] const GIMBAL_MANAGER_FLAGS_PITCH_LOCK = 8 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_LOCK."] const GIMBAL_MANAGER_FLAGS_YAW_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_VEHICLE_FRAME = 32 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_YAW_IN_EARTH_FRAME = 64 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_FLAGS_ACCEPTS_YAW_IN_EARTH_FRAME = 128 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_EXCLUSIVE."] const GIMBAL_MANAGER_FLAGS_RC_EXCLUSIVE = 256 ; # [doc = "Based on GIMBAL_DEVICE_FLAGS_RC_MIXED."] const GIMBAL_MANAGER_FLAGS_RC_MIXED = 512 ; } }
3078impl GimbalManagerFlags {
3079 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_FLAGS_RETRACT;
3080}
3081impl Default for GimbalManagerFlags {
3082 fn default() -> Self {
3083 Self::DEFAULT
3084 }
3085}
3086#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3087#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3088#[cfg_attr(feature = "serde", serde(tag = "type"))]
3089#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3090#[repr(u32)]
3091#[doc = "Enumeration for battery charge states."]
3092pub enum MavBatteryChargeState {
3093 #[doc = "Low battery state is not provided"]
3094 MAV_BATTERY_CHARGE_STATE_UNDEFINED = 0,
3095 #[doc = "Battery is not in low state. Normal operation."]
3096 MAV_BATTERY_CHARGE_STATE_OK = 1,
3097 #[doc = "Battery state is low, warn and monitor close."]
3098 MAV_BATTERY_CHARGE_STATE_LOW = 2,
3099 #[doc = "Battery state is critical, return or abort immediately."]
3100 MAV_BATTERY_CHARGE_STATE_CRITICAL = 3,
3101 #[doc = "Battery state is too low for ordinary abort sequence. Perform fastest possible emergency stop to prevent damage."]
3102 MAV_BATTERY_CHARGE_STATE_EMERGENCY = 4,
3103 #[doc = "Battery failed, damage unavoidable. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
3104 MAV_BATTERY_CHARGE_STATE_FAILED = 5,
3105 #[doc = "Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in MAV_BATTERY_FAULT."]
3106 MAV_BATTERY_CHARGE_STATE_UNHEALTHY = 6,
3107 #[doc = "Battery is charging."]
3108 MAV_BATTERY_CHARGE_STATE_CHARGING = 7,
3109}
3110impl MavBatteryChargeState {
3111 pub const DEFAULT: Self = Self::MAV_BATTERY_CHARGE_STATE_UNDEFINED;
3112}
3113impl Default for MavBatteryChargeState {
3114 fn default() -> Self {
3115 Self::DEFAULT
3116 }
3117}
3118#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3119#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3120#[cfg_attr(feature = "serde", serde(tag = "type"))]
3121#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3122#[repr(u32)]
3123#[doc = "Fuel types for use in FUEL_TYPE. Fuel types specify the units for the maximum, available and consumed fuel, and for the flow rates."]
3124pub enum MavFuelType {
3125 #[doc = "Not specified. Fuel levels are normalized (i.e. maximum is 1, and other levels are relative to 1)."]
3126 MAV_FUEL_TYPE_UNKNOWN = 0,
3127 #[doc = "A generic liquid fuel. Fuel levels are in millilitres (ml). Fuel rates are in millilitres/second."]
3128 MAV_FUEL_TYPE_LIQUID = 1,
3129 #[doc = "A gas tank. Fuel levels are in kilo-Pascal (kPa), and flow rates are in milliliters per second (ml/s)."]
3130 MAV_FUEL_TYPE_GAS = 2,
3131}
3132impl MavFuelType {
3133 pub const DEFAULT: Self = Self::MAV_FUEL_TYPE_UNKNOWN;
3134}
3135impl Default for MavFuelType {
3136 fn default() -> Self {
3137 Self::DEFAULT
3138 }
3139}
3140#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3141#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3142#[cfg_attr(feature = "serde", serde(tag = "type"))]
3143#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3144#[repr(u32)]
3145#[doc = "Battery mode. Note, the normal operation mode (i.e. when flying) should be reported as MAV_BATTERY_MODE_UNKNOWN to allow message trimming in normal flight."]
3146pub enum MavBatteryMode {
3147 #[doc = "Battery mode not supported/unknown battery mode/normal operation."]
3148 MAV_BATTERY_MODE_UNKNOWN = 0,
3149 #[doc = "Battery is auto discharging (towards storage level)."]
3150 MAV_BATTERY_MODE_AUTO_DISCHARGING = 1,
3151 #[doc = "Battery in hot-swap mode (current limited to prevent spikes that might damage sensitive electrical circuits)."]
3152 MAV_BATTERY_MODE_HOT_SWAP = 2,
3153}
3154impl MavBatteryMode {
3155 pub const DEFAULT: Self = Self::MAV_BATTERY_MODE_UNKNOWN;
3156}
3157impl Default for MavBatteryMode {
3158 fn default() -> Self {
3159 Self::DEFAULT
3160 }
3161}
3162#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3163#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3164#[cfg_attr(feature = "serde", serde(tag = "type"))]
3165#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3166#[repr(u32)]
3167#[doc = "Actions for reading/writing parameters between persistent and volatile storage when using MAV_CMD_PREFLIGHT_STORAGE. (Commonly parameters are loaded from persistent storage (flash/EEPROM) into volatile storage (RAM) on startup and written back when they are changed.)"]
3168pub enum PreflightStorageParameterAction {
3169 #[doc = "Read all parameters from persistent storage. Replaces values in volatile storage."]
3170 PARAM_READ_PERSISTENT = 0,
3171 #[doc = "Write all parameter values to persistent storage (flash/EEPROM)"]
3172 PARAM_WRITE_PERSISTENT = 1,
3173 #[doc = "Reset all user configurable parameters to their default value (including airframe selection, sensor calibration data, safety settings, and so on). Does not reset values that contain operation counters and vehicle computed statistics."]
3174 PARAM_RESET_CONFIG_DEFAULT = 2,
3175 #[doc = "Reset only sensor calibration parameters to factory defaults (or firmware default if not available)"]
3176 PARAM_RESET_SENSOR_DEFAULT = 3,
3177 #[doc = "Reset all parameters, including operation counters, to default values"]
3178 PARAM_RESET_ALL_DEFAULT = 4,
3179}
3180impl PreflightStorageParameterAction {
3181 pub const DEFAULT: Self = Self::PARAM_READ_PERSISTENT;
3182}
3183impl Default for PreflightStorageParameterAction {
3184 fn default() -> Self {
3185 Self::DEFAULT
3186 }
3187}
3188#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3189#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3190#[cfg_attr(feature = "serde", serde(tag = "type"))]
3191#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3192#[repr(u32)]
3193#[doc = "List of possible failure type to inject."]
3194pub enum FailureType {
3195 #[doc = "No failure injected, used to reset a previous failure."]
3196 FAILURE_TYPE_OK = 0,
3197 #[doc = "Sets unit off, so completely non-responsive."]
3198 FAILURE_TYPE_OFF = 1,
3199 #[doc = "Unit is stuck e.g. keeps reporting the same value."]
3200 FAILURE_TYPE_STUCK = 2,
3201 #[doc = "Unit is reporting complete garbage."]
3202 FAILURE_TYPE_GARBAGE = 3,
3203 #[doc = "Unit is consistently wrong."]
3204 FAILURE_TYPE_WRONG = 4,
3205 #[doc = "Unit is slow, so e.g. reporting at slower than expected rate."]
3206 FAILURE_TYPE_SLOW = 5,
3207 #[doc = "Data of unit is delayed in time."]
3208 FAILURE_TYPE_DELAYED = 6,
3209 #[doc = "Unit is sometimes working, sometimes not."]
3210 FAILURE_TYPE_INTERMITTENT = 7,
3211}
3212impl FailureType {
3213 pub const DEFAULT: Self = Self::FAILURE_TYPE_OK;
3214}
3215impl Default for FailureType {
3216 fn default() -> Self {
3217 Self::DEFAULT
3218 }
3219}
3220#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3221#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3222#[cfg_attr(feature = "serde", serde(tag = "type"))]
3223#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3224#[repr(u32)]
3225#[doc = "Cellular network radio type"]
3226pub enum CellularNetworkRadioType {
3227 CELLULAR_NETWORK_RADIO_TYPE_NONE = 0,
3228 CELLULAR_NETWORK_RADIO_TYPE_GSM = 1,
3229 CELLULAR_NETWORK_RADIO_TYPE_CDMA = 2,
3230 CELLULAR_NETWORK_RADIO_TYPE_WCDMA = 3,
3231 CELLULAR_NETWORK_RADIO_TYPE_LTE = 4,
3232}
3233impl CellularNetworkRadioType {
3234 pub const DEFAULT: Self = Self::CELLULAR_NETWORK_RADIO_TYPE_NONE;
3235}
3236impl Default for CellularNetworkRadioType {
3237 fn default() -> Self {
3238 Self::DEFAULT
3239 }
3240}
3241#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3242#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3243#[cfg_attr(feature = "serde", serde(tag = "type"))]
3244#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3245#[repr(u32)]
3246#[doc = "Actions being taken to mitigate/prevent fence breach"]
3247pub enum FenceMitigate {
3248 #[doc = "Unknown"]
3249 FENCE_MITIGATE_UNKNOWN = 0,
3250 #[doc = "No actions being taken"]
3251 FENCE_MITIGATE_NONE = 1,
3252 #[doc = "Velocity limiting active to prevent breach"]
3253 FENCE_MITIGATE_VEL_LIMIT = 2,
3254}
3255impl FenceMitigate {
3256 pub const DEFAULT: Self = Self::FENCE_MITIGATE_UNKNOWN;
3257}
3258impl Default for FenceMitigate {
3259 fn default() -> Self {
3260 Self::DEFAULT
3261 }
3262}
3263#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3264#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3265#[cfg_attr(feature = "serde", serde(tag = "type"))]
3266#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3267#[repr(u32)]
3268#[doc = "Sequence that motors are tested when using MAV_CMD_DO_MOTOR_TEST."]
3269pub enum MotorTestOrder {
3270 #[doc = "Default autopilot motor test method."]
3271 MOTOR_TEST_ORDER_DEFAULT = 0,
3272 #[doc = "Motor numbers are specified as their index in a predefined vehicle-specific sequence."]
3273 MOTOR_TEST_ORDER_SEQUENCE = 1,
3274 #[doc = "Motor numbers are specified as the output as labeled on the board."]
3275 MOTOR_TEST_ORDER_BOARD = 2,
3276}
3277impl MotorTestOrder {
3278 pub const DEFAULT: Self = Self::MOTOR_TEST_ORDER_DEFAULT;
3279}
3280impl Default for MotorTestOrder {
3281 fn default() -> Self {
3282 Self::DEFAULT
3283 }
3284}
3285#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3286#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3287#[cfg_attr(feature = "serde", serde(tag = "type"))]
3288#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3289#[repr(u32)]
3290#[doc = "Specifies the datatype of a MAVLink extended parameter."]
3291pub enum MavParamExtType {
3292 #[doc = "8-bit unsigned integer"]
3293 MAV_PARAM_EXT_TYPE_UINT8 = 1,
3294 #[doc = "8-bit signed integer"]
3295 MAV_PARAM_EXT_TYPE_INT8 = 2,
3296 #[doc = "16-bit unsigned integer"]
3297 MAV_PARAM_EXT_TYPE_UINT16 = 3,
3298 #[doc = "16-bit signed integer"]
3299 MAV_PARAM_EXT_TYPE_INT16 = 4,
3300 #[doc = "32-bit unsigned integer"]
3301 MAV_PARAM_EXT_TYPE_UINT32 = 5,
3302 #[doc = "32-bit signed integer"]
3303 MAV_PARAM_EXT_TYPE_INT32 = 6,
3304 #[doc = "64-bit unsigned integer"]
3305 MAV_PARAM_EXT_TYPE_UINT64 = 7,
3306 #[doc = "64-bit signed integer"]
3307 MAV_PARAM_EXT_TYPE_INT64 = 8,
3308 #[doc = "32-bit floating-point"]
3309 MAV_PARAM_EXT_TYPE_REAL32 = 9,
3310 #[doc = "64-bit floating-point"]
3311 MAV_PARAM_EXT_TYPE_REAL64 = 10,
3312 #[doc = "Custom Type"]
3313 MAV_PARAM_EXT_TYPE_CUSTOM = 11,
3314}
3315impl MavParamExtType {
3316 pub const DEFAULT: Self = Self::MAV_PARAM_EXT_TYPE_UINT8;
3317}
3318impl Default for MavParamExtType {
3319 fn default() -> Self {
3320 Self::DEFAULT
3321 }
3322}
3323bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Bitmap to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 9 is set the floats afx afy afz should be interpreted as force instead of acceleration."] pub struct PositionTargetTypemask : u16 { # [doc = "Ignore position x"] const POSITION_TARGET_TYPEMASK_X_IGNORE = 1 ; # [doc = "Ignore position y"] const POSITION_TARGET_TYPEMASK_Y_IGNORE = 2 ; # [doc = "Ignore position z"] const POSITION_TARGET_TYPEMASK_Z_IGNORE = 4 ; # [doc = "Ignore velocity x"] const POSITION_TARGET_TYPEMASK_VX_IGNORE = 8 ; # [doc = "Ignore velocity y"] const POSITION_TARGET_TYPEMASK_VY_IGNORE = 16 ; # [doc = "Ignore velocity z"] const POSITION_TARGET_TYPEMASK_VZ_IGNORE = 32 ; # [doc = "Ignore acceleration x"] const POSITION_TARGET_TYPEMASK_AX_IGNORE = 64 ; # [doc = "Ignore acceleration y"] const POSITION_TARGET_TYPEMASK_AY_IGNORE = 128 ; # [doc = "Ignore acceleration z"] const POSITION_TARGET_TYPEMASK_AZ_IGNORE = 256 ; # [doc = "Use force instead of acceleration"] const POSITION_TARGET_TYPEMASK_FORCE_SET = 512 ; # [doc = "Ignore yaw"] const POSITION_TARGET_TYPEMASK_YAW_IGNORE = 1024 ; # [doc = "Ignore yaw rate"] const POSITION_TARGET_TYPEMASK_YAW_RATE_IGNORE = 2048 ; } }
3324impl PositionTargetTypemask {
3325 pub const DEFAULT: Self = Self::POSITION_TARGET_TYPEMASK_X_IGNORE;
3326}
3327impl Default for PositionTargetTypemask {
3328 fn default() -> Self {
3329 Self::DEFAULT
3330 }
3331}
3332bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Gimbal manager high level capability flags (bitmap). The first 16 bits are identical to the GIMBAL_DEVICE_CAP_FLAGS. However, the gimbal manager does not need to copy the flags from the gimbal but can also enhance the capabilities and thus add flags."] pub struct GimbalManagerCapFlags : u32 { # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RETRACT."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT = 1 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_NEUTRAL."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_NEUTRAL = 2 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_AXIS = 4 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_FOLLOW = 8 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_ROLL_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_ROLL_LOCK = 16 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_AXIS = 32 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_FOLLOW = 64 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_PITCH_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_PITCH_LOCK = 128 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_AXIS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_AXIS = 256 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_FOLLOW."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_FOLLOW = 512 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_YAW_LOCK."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_YAW_LOCK = 1024 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_INFINITE_YAW."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_INFINITE_YAW = 2048 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME."] const GIMBAL_MANAGER_CAP_FLAGS_SUPPORTS_YAW_IN_EARTH_FRAME = 4096 ; # [doc = "Based on GIMBAL_DEVICE_CAP_FLAGS_HAS_RC_INPUTS."] const GIMBAL_MANAGER_CAP_FLAGS_HAS_RC_INPUTS = 8192 ; # [doc = "Gimbal manager supports to point to a local position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_LOCAL = 65536 ; # [doc = "Gimbal manager supports to point to a global latitude, longitude, altitude position."] const GIMBAL_MANAGER_CAP_FLAGS_CAN_POINT_LOCATION_GLOBAL = 131072 ; } }
3333impl GimbalManagerCapFlags {
3334 pub const DEFAULT: Self = Self::GIMBAL_MANAGER_CAP_FLAGS_HAS_RETRACT;
3335}
3336impl Default for GimbalManagerCapFlags {
3337 fn default() -> Self {
3338 Self::DEFAULT
3339 }
3340}
3341bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to indicate usage for a particular storage (see STORAGE_INFORMATION.storage_usage and MAV_CMD_SET_STORAGE_USAGE)."] pub struct StorageUsageFlag : u8 { # [doc = "Always set to 1 (indicates STORAGE_INFORMATION.storage_usage is supported)."] const STORAGE_USAGE_FLAG_SET = 1 ; # [doc = "Storage for saving photos."] const STORAGE_USAGE_FLAG_PHOTO = 2 ; # [doc = "Storage for saving videos."] const STORAGE_USAGE_FLAG_VIDEO = 4 ; # [doc = "Storage for saving logs."] const STORAGE_USAGE_FLAG_LOGS = 8 ; } }
3342impl StorageUsageFlag {
3343 pub const DEFAULT: Self = Self::STORAGE_USAGE_FLAG_SET;
3344}
3345impl Default for StorageUsageFlag {
3346 fn default() -> Self {
3347 Self::DEFAULT
3348 }
3349}
3350#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3351#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3352#[cfg_attr(feature = "serde", serde(tag = "type"))]
3353#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3354#[repr(u32)]
3355#[doc = "Result from a MAVLink command (MAV_CMD)"]
3356pub enum MavResult {
3357 #[doc = "Command is valid (is supported and has valid parameters), and was executed."]
3358 MAV_RESULT_ACCEPTED = 0,
3359 #[doc = "Command is valid, but cannot be executed at this time. This is used to indicate a problem that should be fixed just by waiting (e.g. a state machine is busy, can't arm because have not got GPS lock, etc.). Retrying later should work."]
3360 MAV_RESULT_TEMPORARILY_REJECTED = 1,
3361 #[doc = "Command is invalid (is supported but has invalid parameters). Retrying same command and parameters will not work."]
3362 MAV_RESULT_DENIED = 2,
3363 #[doc = "Command is not supported (unknown)."]
3364 MAV_RESULT_UNSUPPORTED = 3,
3365 #[doc = "Command is valid, but execution has failed. This is used to indicate any non-temporary or unexpected problem, i.e. any problem that must be fixed before the command can succeed/be retried. For example, attempting to write a file when out of memory, attempting to arm when sensors are not calibrated, etc."]
3366 MAV_RESULT_FAILED = 4,
3367 #[doc = "Command is valid and is being executed. This will be followed by further progress updates, i.e. the component may send further COMMAND_ACK messages with result MAV_RESULT_IN_PROGRESS (at a rate decided by the implementation), and must terminate by sending a COMMAND_ACK message with final result of the operation. The COMMAND_ACK.progress field can be used to indicate the progress of the operation."]
3368 MAV_RESULT_IN_PROGRESS = 5,
3369 #[doc = "Command has been cancelled (as a result of receiving a COMMAND_CANCEL message)."]
3370 MAV_RESULT_CANCELLED = 6,
3371 #[doc = "Command is only accepted when sent as a COMMAND_LONG."]
3372 MAV_RESULT_COMMAND_LONG_ONLY = 7,
3373 #[doc = "Command is only accepted when sent as a COMMAND_INT."]
3374 MAV_RESULT_COMMAND_INT_ONLY = 8,
3375 #[doc = "Command is invalid because a frame is required and the specified frame is not supported."]
3376 MAV_RESULT_COMMAND_UNSUPPORTED_MAV_FRAME = 9,
3377}
3378impl MavResult {
3379 pub const DEFAULT: Self = Self::MAV_RESULT_ACCEPTED;
3380}
3381impl Default for MavResult {
3382 fn default() -> Self {
3383 Self::DEFAULT
3384 }
3385}
3386#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3387#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3388#[cfg_attr(feature = "serde", serde(tag = "type"))]
3389#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3390#[repr(u32)]
3391#[doc = "Actions that may be specified in MAV_CMD_OVERRIDE_GOTO to override mission execution."]
3392pub enum MavGoto {
3393 #[doc = "Hold at the current position."]
3394 MAV_GOTO_DO_HOLD = 0,
3395 #[doc = "Continue with the next item in mission execution."]
3396 MAV_GOTO_DO_CONTINUE = 1,
3397 #[doc = "Hold at the current position of the system"]
3398 MAV_GOTO_HOLD_AT_CURRENT_POSITION = 2,
3399 #[doc = "Hold at the position specified in the parameters of the DO_HOLD action"]
3400 MAV_GOTO_HOLD_AT_SPECIFIED_POSITION = 3,
3401}
3402impl MavGoto {
3403 pub const DEFAULT: Self = Self::MAV_GOTO_DO_HOLD;
3404}
3405impl Default for MavGoto {
3406 fn default() -> Self {
3407 Self::DEFAULT
3408 }
3409}
3410#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3411#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3412#[cfg_attr(feature = "serde", serde(tag = "type"))]
3413#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3414#[repr(u32)]
3415#[doc = "These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not."]
3416pub enum MavModeFlagDecodePosition {
3417 #[doc = "First bit: 10000000"]
3418 MAV_MODE_FLAG_DECODE_POSITION_SAFETY = 128,
3419 #[doc = "Second bit: 01000000"]
3420 MAV_MODE_FLAG_DECODE_POSITION_MANUAL = 64,
3421 #[doc = "Third bit: 00100000"]
3422 MAV_MODE_FLAG_DECODE_POSITION_HIL = 32,
3423 #[doc = "Fourth bit: 00010000"]
3424 MAV_MODE_FLAG_DECODE_POSITION_STABILIZE = 16,
3425 #[doc = "Fifth bit: 00001000"]
3426 MAV_MODE_FLAG_DECODE_POSITION_GUIDED = 8,
3427 #[doc = "Sixth bit: 00000100"]
3428 MAV_MODE_FLAG_DECODE_POSITION_AUTO = 4,
3429 #[doc = "Seventh bit: 00000010"]
3430 MAV_MODE_FLAG_DECODE_POSITION_TEST = 2,
3431 #[doc = "Eighth bit: 00000001"]
3432 MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE = 1,
3433}
3434impl MavModeFlagDecodePosition {
3435 pub const DEFAULT: Self = Self::MAV_MODE_FLAG_DECODE_POSITION_SAFETY;
3436}
3437impl Default for MavModeFlagDecodePosition {
3438 fn default() -> Self {
3439 Self::DEFAULT
3440 }
3441}
3442#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3443#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3444#[cfg_attr(feature = "serde", serde(tag = "type"))]
3445#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3446#[repr(u32)]
3447#[doc = "These flags encode the cellular network status"]
3448pub enum CellularStatusFlag {
3449 #[doc = "State unknown or not reportable."]
3450 CELLULAR_STATUS_FLAG_UNKNOWN = 0,
3451 #[doc = "Modem is unusable"]
3452 CELLULAR_STATUS_FLAG_FAILED = 1,
3453 #[doc = "Modem is being initialized"]
3454 CELLULAR_STATUS_FLAG_INITIALIZING = 2,
3455 #[doc = "Modem is locked"]
3456 CELLULAR_STATUS_FLAG_LOCKED = 3,
3457 #[doc = "Modem is not enabled and is powered down"]
3458 CELLULAR_STATUS_FLAG_DISABLED = 4,
3459 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_DISABLED state"]
3460 CELLULAR_STATUS_FLAG_DISABLING = 5,
3461 #[doc = "Modem is currently transitioning to the CELLULAR_STATUS_FLAG_ENABLED state"]
3462 CELLULAR_STATUS_FLAG_ENABLING = 6,
3463 #[doc = "Modem is enabled and powered on but not registered with a network provider and not available for data connections"]
3464 CELLULAR_STATUS_FLAG_ENABLED = 7,
3465 #[doc = "Modem is searching for a network provider to register"]
3466 CELLULAR_STATUS_FLAG_SEARCHING = 8,
3467 #[doc = "Modem is registered with a network provider, and data connections and messaging may be available for use"]
3468 CELLULAR_STATUS_FLAG_REGISTERED = 9,
3469 #[doc = "Modem is disconnecting and deactivating the last active packet data bearer. This state will not be entered if more than one packet data bearer is active and one of the active bearers is deactivated"]
3470 CELLULAR_STATUS_FLAG_DISCONNECTING = 10,
3471 #[doc = "Modem is activating and connecting the first packet data bearer. Subsequent bearer activations when another bearer is already active do not cause this state to be entered"]
3472 CELLULAR_STATUS_FLAG_CONNECTING = 11,
3473 #[doc = "One or more packet data bearers is active and connected"]
3474 CELLULAR_STATUS_FLAG_CONNECTED = 12,
3475}
3476impl CellularStatusFlag {
3477 pub const DEFAULT: Self = Self::CELLULAR_STATUS_FLAG_UNKNOWN;
3478}
3479impl Default for CellularStatusFlag {
3480 fn default() -> Self {
3481 Self::DEFAULT
3482 }
3483}
3484#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3485#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3486#[cfg_attr(feature = "serde", serde(tag = "type"))]
3487#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3488#[repr(u32)]
3489#[doc = "Precision land modes (used in MAV_CMD_NAV_LAND)."]
3490pub enum PrecisionLandMode {
3491 #[doc = "Normal (non-precision) landing."]
3492 PRECISION_LAND_MODE_DISABLED = 0,
3493 #[doc = "Use precision landing if beacon detected when land command accepted, otherwise land normally."]
3494 PRECISION_LAND_MODE_OPPORTUNISTIC = 1,
3495 #[doc = "Use precision landing, searching for beacon if not found when land command accepted (land normally if beacon cannot be found)."]
3496 PRECISION_LAND_MODE_REQUIRED = 2,
3497}
3498impl PrecisionLandMode {
3499 pub const DEFAULT: Self = Self::PRECISION_LAND_MODE_DISABLED;
3500}
3501impl Default for PrecisionLandMode {
3502 fn default() -> Self {
3503 Self::DEFAULT
3504 }
3505}
3506bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] pub struct GpsInputIgnoreFlags : u16 { # [doc = "ignore altitude field"] const GPS_INPUT_IGNORE_FLAG_ALT = 1 ; # [doc = "ignore hdop field"] const GPS_INPUT_IGNORE_FLAG_HDOP = 2 ; # [doc = "ignore vdop field"] const GPS_INPUT_IGNORE_FLAG_VDOP = 4 ; # [doc = "ignore horizontal velocity field (vn and ve)"] const GPS_INPUT_IGNORE_FLAG_VEL_HORIZ = 8 ; # [doc = "ignore vertical velocity field (vd)"] const GPS_INPUT_IGNORE_FLAG_VEL_VERT = 16 ; # [doc = "ignore speed accuracy field"] const GPS_INPUT_IGNORE_FLAG_SPEED_ACCURACY = 32 ; # [doc = "ignore horizontal accuracy field"] const GPS_INPUT_IGNORE_FLAG_HORIZONTAL_ACCURACY = 64 ; # [doc = "ignore vertical accuracy field"] const GPS_INPUT_IGNORE_FLAG_VERTICAL_ACCURACY = 128 ; } }
3507impl GpsInputIgnoreFlags {
3508 pub const DEFAULT: Self = Self::GPS_INPUT_IGNORE_FLAG_ALT;
3509}
3510impl Default for GpsInputIgnoreFlags {
3511 fn default() -> Self {
3512 Self::DEFAULT
3513 }
3514}
3515#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3516#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3517#[cfg_attr(feature = "serde", serde(tag = "type"))]
3518#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3519#[repr(u32)]
3520#[doc = "Yaw behaviour during orbit flight."]
3521pub enum OrbitYawBehaviour {
3522 #[doc = "Vehicle front points to the center (default)."]
3523 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER = 0,
3524 #[doc = "Vehicle front holds heading when message received."]
3525 ORBIT_YAW_BEHAVIOUR_HOLD_INITIAL_HEADING = 1,
3526 #[doc = "Yaw uncontrolled."]
3527 ORBIT_YAW_BEHAVIOUR_UNCONTROLLED = 2,
3528 #[doc = "Vehicle front follows flight path (tangential to circle)."]
3529 ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TANGENT_TO_CIRCLE = 3,
3530 #[doc = "Yaw controlled by RC input."]
3531 ORBIT_YAW_BEHAVIOUR_RC_CONTROLLED = 4,
3532 #[doc = "Vehicle uses current yaw behaviour (unchanged). The vehicle-default yaw behaviour is used if this value is specified when orbit is first commanded."]
3533 ORBIT_YAW_BEHAVIOUR_UNCHANGED = 5,
3534}
3535impl OrbitYawBehaviour {
3536 pub const DEFAULT: Self = Self::ORBIT_YAW_BEHAVIOUR_HOLD_FRONT_TO_CIRCLE_CENTER;
3537}
3538impl Default for OrbitYawBehaviour {
3539 fn default() -> Self {
3540 Self::DEFAULT
3541 }
3542}
3543#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3544#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3545#[cfg_attr(feature = "serde", serde(tag = "type"))]
3546#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3547#[repr(u32)]
3548#[doc = "These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override."]
3549pub enum MavMode {
3550 #[doc = "System is not ready to fly, booting, calibrating, etc. No flag is set."]
3551 MAV_MODE_PREFLIGHT = 0,
3552 #[doc = "System is allowed to be active, under assisted RC control."]
3553 MAV_MODE_STABILIZE_DISARMED = 80,
3554 #[doc = "System is allowed to be active, under assisted RC control."]
3555 MAV_MODE_STABILIZE_ARMED = 208,
3556 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
3557 MAV_MODE_MANUAL_DISARMED = 64,
3558 #[doc = "System is allowed to be active, under manual (RC) control, no stabilization"]
3559 MAV_MODE_MANUAL_ARMED = 192,
3560 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
3561 MAV_MODE_GUIDED_DISARMED = 88,
3562 #[doc = "System is allowed to be active, under autonomous control, manual setpoint"]
3563 MAV_MODE_GUIDED_ARMED = 216,
3564 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
3565 MAV_MODE_AUTO_DISARMED = 92,
3566 #[doc = "System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by waypoints)"]
3567 MAV_MODE_AUTO_ARMED = 220,
3568 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
3569 MAV_MODE_TEST_DISARMED = 66,
3570 #[doc = "UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only."]
3571 MAV_MODE_TEST_ARMED = 194,
3572}
3573impl MavMode {
3574 pub const DEFAULT: Self = Self::MAV_MODE_PREFLIGHT;
3575}
3576impl Default for MavMode {
3577 fn default() -> Self {
3578 Self::DEFAULT
3579 }
3580}
3581#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3582#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3583#[cfg_attr(feature = "serde", serde(tag = "type"))]
3584#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3585#[repr(u32)]
3586#[doc = "Camera sources for MAV_CMD_SET_CAMERA_SOURCE"]
3587pub enum CameraSource {
3588 #[doc = "Default camera source."]
3589 CAMERA_SOURCE_DEFAULT = 0,
3590 #[doc = "RGB camera source."]
3591 CAMERA_SOURCE_RGB = 1,
3592 #[doc = "IR camera source."]
3593 CAMERA_SOURCE_IR = 2,
3594 #[doc = "NDVI camera source."]
3595 CAMERA_SOURCE_NDVI = 3,
3596}
3597impl CameraSource {
3598 pub const DEFAULT: Self = Self::CAMERA_SOURCE_DEFAULT;
3599}
3600impl Default for CameraSource {
3601 fn default() -> Self {
3602 Self::DEFAULT
3603 }
3604}
3605bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Mode properties."] pub struct MavModeProperty : u32 { # [doc = "If set, this mode is an advanced mode. For example a rate-controlled manual mode might be advanced, whereas a position-controlled manual mode is not. A GCS can optionally use this flag to configure the UI for its intended users."] const MAV_MODE_PROPERTY_ADVANCED = 1 ; # [doc = "If set, this mode should not be added to the list of selectable modes. The mode might still be selected by the FC directly (for example as part of a failsafe)."] const MAV_MODE_PROPERTY_NOT_USER_SELECTABLE = 2 ; # [doc = "If set, this mode is automatically controlled (it may use but does not require a manual controller). If unset the mode is a assumed to require user input (be a manual mode)."] const MAV_MODE_PROPERTY_AUTO_MODE = 4 ; } }
3606impl MavModeProperty {
3607 pub const DEFAULT: Self = Self::MAV_MODE_PROPERTY_ADVANCED;
3608}
3609impl Default for MavModeProperty {
3610 fn default() -> Self {
3611 Self::DEFAULT
3612 }
3613}
3614#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3615#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3616#[cfg_attr(feature = "serde", serde(tag = "type"))]
3617#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3618#[repr(u32)]
3619#[doc = "Enumeration of battery functions"]
3620pub enum MavBatteryFunction {
3621 #[doc = "Battery function is unknown"]
3622 MAV_BATTERY_FUNCTION_UNKNOWN = 0,
3623 #[doc = "Battery supports all flight systems"]
3624 MAV_BATTERY_FUNCTION_ALL = 1,
3625 #[doc = "Battery for the propulsion system"]
3626 MAV_BATTERY_FUNCTION_PROPULSION = 2,
3627 #[doc = "Avionics battery"]
3628 MAV_BATTERY_FUNCTION_AVIONICS = 3,
3629 #[doc = "Payload battery"]
3630 MAV_BATTERY_FUNCTION_PAYLOAD = 4,
3631}
3632impl MavBatteryFunction {
3633 pub const DEFAULT: Self = Self::MAV_BATTERY_FUNCTION_UNKNOWN;
3634}
3635impl Default for MavBatteryFunction {
3636 fn default() -> Self {
3637 Self::DEFAULT
3638 }
3639}
3640#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3641#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3642#[cfg_attr(feature = "serde", serde(tag = "type"))]
3643#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3644#[repr(u32)]
3645#[doc = "Aircraft-rated danger from this threat."]
3646pub enum MavCollisionThreatLevel {
3647 #[doc = "Not a threat"]
3648 MAV_COLLISION_THREAT_LEVEL_NONE = 0,
3649 #[doc = "Craft is mildly concerned about this threat"]
3650 MAV_COLLISION_THREAT_LEVEL_LOW = 1,
3651 #[doc = "Craft is panicking, and may take actions to avoid threat"]
3652 MAV_COLLISION_THREAT_LEVEL_HIGH = 2,
3653}
3654impl MavCollisionThreatLevel {
3655 pub const DEFAULT: Self = Self::MAV_COLLISION_THREAT_LEVEL_NONE;
3656}
3657impl Default for MavCollisionThreatLevel {
3658 fn default() -> Self {
3659 Self::DEFAULT
3660 }
3661}
3662#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3663#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3664#[cfg_attr(feature = "serde", serde(tag = "type"))]
3665#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3666#[repr(u32)]
3667#[doc = "Enumeration of sensor orientation, according to its rotations"]
3668pub enum MavSensorOrientation {
3669 #[doc = "Roll: 0, Pitch: 0, Yaw: 0"]
3670 MAV_SENSOR_ROTATION_NONE = 0,
3671 #[doc = "Roll: 0, Pitch: 0, Yaw: 45"]
3672 MAV_SENSOR_ROTATION_YAW_45 = 1,
3673 #[doc = "Roll: 0, Pitch: 0, Yaw: 90"]
3674 MAV_SENSOR_ROTATION_YAW_90 = 2,
3675 #[doc = "Roll: 0, Pitch: 0, Yaw: 135"]
3676 MAV_SENSOR_ROTATION_YAW_135 = 3,
3677 #[doc = "Roll: 0, Pitch: 0, Yaw: 180"]
3678 MAV_SENSOR_ROTATION_YAW_180 = 4,
3679 #[doc = "Roll: 0, Pitch: 0, Yaw: 225"]
3680 MAV_SENSOR_ROTATION_YAW_225 = 5,
3681 #[doc = "Roll: 0, Pitch: 0, Yaw: 270"]
3682 MAV_SENSOR_ROTATION_YAW_270 = 6,
3683 #[doc = "Roll: 0, Pitch: 0, Yaw: 315"]
3684 MAV_SENSOR_ROTATION_YAW_315 = 7,
3685 #[doc = "Roll: 180, Pitch: 0, Yaw: 0"]
3686 MAV_SENSOR_ROTATION_ROLL_180 = 8,
3687 #[doc = "Roll: 180, Pitch: 0, Yaw: 45"]
3688 MAV_SENSOR_ROTATION_ROLL_180_YAW_45 = 9,
3689 #[doc = "Roll: 180, Pitch: 0, Yaw: 90"]
3690 MAV_SENSOR_ROTATION_ROLL_180_YAW_90 = 10,
3691 #[doc = "Roll: 180, Pitch: 0, Yaw: 135"]
3692 MAV_SENSOR_ROTATION_ROLL_180_YAW_135 = 11,
3693 #[doc = "Roll: 0, Pitch: 180, Yaw: 0"]
3694 MAV_SENSOR_ROTATION_PITCH_180 = 12,
3695 #[doc = "Roll: 180, Pitch: 0, Yaw: 225"]
3696 MAV_SENSOR_ROTATION_ROLL_180_YAW_225 = 13,
3697 #[doc = "Roll: 180, Pitch: 0, Yaw: 270"]
3698 MAV_SENSOR_ROTATION_ROLL_180_YAW_270 = 14,
3699 #[doc = "Roll: 180, Pitch: 0, Yaw: 315"]
3700 MAV_SENSOR_ROTATION_ROLL_180_YAW_315 = 15,
3701 #[doc = "Roll: 90, Pitch: 0, Yaw: 0"]
3702 MAV_SENSOR_ROTATION_ROLL_90 = 16,
3703 #[doc = "Roll: 90, Pitch: 0, Yaw: 45"]
3704 MAV_SENSOR_ROTATION_ROLL_90_YAW_45 = 17,
3705 #[doc = "Roll: 90, Pitch: 0, Yaw: 90"]
3706 MAV_SENSOR_ROTATION_ROLL_90_YAW_90 = 18,
3707 #[doc = "Roll: 90, Pitch: 0, Yaw: 135"]
3708 MAV_SENSOR_ROTATION_ROLL_90_YAW_135 = 19,
3709 #[doc = "Roll: 270, Pitch: 0, Yaw: 0"]
3710 MAV_SENSOR_ROTATION_ROLL_270 = 20,
3711 #[doc = "Roll: 270, Pitch: 0, Yaw: 45"]
3712 MAV_SENSOR_ROTATION_ROLL_270_YAW_45 = 21,
3713 #[doc = "Roll: 270, Pitch: 0, Yaw: 90"]
3714 MAV_SENSOR_ROTATION_ROLL_270_YAW_90 = 22,
3715 #[doc = "Roll: 270, Pitch: 0, Yaw: 135"]
3716 MAV_SENSOR_ROTATION_ROLL_270_YAW_135 = 23,
3717 #[doc = "Roll: 0, Pitch: 90, Yaw: 0"]
3718 MAV_SENSOR_ROTATION_PITCH_90 = 24,
3719 #[doc = "Roll: 0, Pitch: 270, Yaw: 0"]
3720 MAV_SENSOR_ROTATION_PITCH_270 = 25,
3721 #[doc = "Roll: 0, Pitch: 180, Yaw: 90"]
3722 MAV_SENSOR_ROTATION_PITCH_180_YAW_90 = 26,
3723 #[doc = "Roll: 0, Pitch: 180, Yaw: 270"]
3724 MAV_SENSOR_ROTATION_PITCH_180_YAW_270 = 27,
3725 #[doc = "Roll: 90, Pitch: 90, Yaw: 0"]
3726 MAV_SENSOR_ROTATION_ROLL_90_PITCH_90 = 28,
3727 #[doc = "Roll: 180, Pitch: 90, Yaw: 0"]
3728 MAV_SENSOR_ROTATION_ROLL_180_PITCH_90 = 29,
3729 #[doc = "Roll: 270, Pitch: 90, Yaw: 0"]
3730 MAV_SENSOR_ROTATION_ROLL_270_PITCH_90 = 30,
3731 #[doc = "Roll: 90, Pitch: 180, Yaw: 0"]
3732 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180 = 31,
3733 #[doc = "Roll: 270, Pitch: 180, Yaw: 0"]
3734 MAV_SENSOR_ROTATION_ROLL_270_PITCH_180 = 32,
3735 #[doc = "Roll: 90, Pitch: 270, Yaw: 0"]
3736 MAV_SENSOR_ROTATION_ROLL_90_PITCH_270 = 33,
3737 #[doc = "Roll: 180, Pitch: 270, Yaw: 0"]
3738 MAV_SENSOR_ROTATION_ROLL_180_PITCH_270 = 34,
3739 #[doc = "Roll: 270, Pitch: 270, Yaw: 0"]
3740 MAV_SENSOR_ROTATION_ROLL_270_PITCH_270 = 35,
3741 #[doc = "Roll: 90, Pitch: 180, Yaw: 90"]
3742 MAV_SENSOR_ROTATION_ROLL_90_PITCH_180_YAW_90 = 36,
3743 #[doc = "Roll: 90, Pitch: 0, Yaw: 270"]
3744 MAV_SENSOR_ROTATION_ROLL_90_YAW_270 = 37,
3745 #[doc = "Roll: 90, Pitch: 68, Yaw: 293"]
3746 MAV_SENSOR_ROTATION_ROLL_90_PITCH_68_YAW_293 = 38,
3747 #[doc = "Pitch: 315"]
3748 MAV_SENSOR_ROTATION_PITCH_315 = 39,
3749 #[doc = "Roll: 90, Pitch: 315"]
3750 MAV_SENSOR_ROTATION_ROLL_90_PITCH_315 = 40,
3751 #[doc = "Custom orientation"]
3752 MAV_SENSOR_ROTATION_CUSTOM = 100,
3753}
3754impl MavSensorOrientation {
3755 pub const DEFAULT: Self = Self::MAV_SENSOR_ROTATION_NONE;
3756}
3757impl Default for MavSensorOrientation {
3758 fn default() -> Self {
3759 Self::DEFAULT
3760 }
3761}
3762#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3763#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3764#[cfg_attr(feature = "serde", serde(tag = "type"))]
3765#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3766#[repr(u32)]
3767#[doc = "Result from PARAM_EXT_SET message."]
3768pub enum ParamAck {
3769 #[doc = "Parameter value ACCEPTED and SET"]
3770 PARAM_ACK_ACCEPTED = 0,
3771 #[doc = "Parameter value UNKNOWN/UNSUPPORTED"]
3772 PARAM_ACK_VALUE_UNSUPPORTED = 1,
3773 #[doc = "Parameter failed to set"]
3774 PARAM_ACK_FAILED = 2,
3775 #[doc = "Parameter value received but not yet set/accepted. A subsequent PARAM_EXT_ACK with the final result will follow once operation is completed. This is returned immediately for parameters that take longer to set, indicating that the the parameter was received and does not need to be resent."]
3776 PARAM_ACK_IN_PROGRESS = 3,
3777}
3778impl ParamAck {
3779 pub const DEFAULT: Self = Self::PARAM_ACK_ACCEPTED;
3780}
3781impl Default for ParamAck {
3782 fn default() -> Self {
3783 Self::DEFAULT
3784 }
3785}
3786#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3787#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3788#[cfg_attr(feature = "serde", serde(tag = "type"))]
3789#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3790#[repr(u32)]
3791#[doc = "SERIAL_CONTROL device types"]
3792pub enum SerialControlDev {
3793 #[doc = "First telemetry port"]
3794 SERIAL_CONTROL_DEV_TELEM1 = 0,
3795 #[doc = "Second telemetry port"]
3796 SERIAL_CONTROL_DEV_TELEM2 = 1,
3797 #[doc = "First GPS port"]
3798 SERIAL_CONTROL_DEV_GPS1 = 2,
3799 #[doc = "Second GPS port"]
3800 SERIAL_CONTROL_DEV_GPS2 = 3,
3801 #[doc = "system shell"]
3802 SERIAL_CONTROL_DEV_SHELL = 10,
3803 #[doc = "SERIAL0"]
3804 SERIAL_CONTROL_SERIAL0 = 100,
3805 #[doc = "SERIAL1"]
3806 SERIAL_CONTROL_SERIAL1 = 101,
3807 #[doc = "SERIAL2"]
3808 SERIAL_CONTROL_SERIAL2 = 102,
3809 #[doc = "SERIAL3"]
3810 SERIAL_CONTROL_SERIAL3 = 103,
3811 #[doc = "SERIAL4"]
3812 SERIAL_CONTROL_SERIAL4 = 104,
3813 #[doc = "SERIAL5"]
3814 SERIAL_CONTROL_SERIAL5 = 105,
3815 #[doc = "SERIAL6"]
3816 SERIAL_CONTROL_SERIAL6 = 106,
3817 #[doc = "SERIAL7"]
3818 SERIAL_CONTROL_SERIAL7 = 107,
3819 #[doc = "SERIAL8"]
3820 SERIAL_CONTROL_SERIAL8 = 108,
3821 #[doc = "SERIAL9"]
3822 SERIAL_CONTROL_SERIAL9 = 109,
3823}
3824impl SerialControlDev {
3825 pub const DEFAULT: Self = Self::SERIAL_CONTROL_DEV_TELEM1;
3826}
3827impl Default for SerialControlDev {
3828 fn default() -> Self {
3829 Self::DEFAULT
3830 }
3831}
3832#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3833#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3834#[cfg_attr(feature = "serde", serde(tag = "type"))]
3835#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3836#[repr(u32)]
3837#[doc = "Enumeration of battery types"]
3838pub enum MavBatteryType {
3839 #[doc = "Not specified."]
3840 MAV_BATTERY_TYPE_UNKNOWN = 0,
3841 #[doc = "Lithium polymer battery"]
3842 MAV_BATTERY_TYPE_LIPO = 1,
3843 #[doc = "Lithium-iron-phosphate battery"]
3844 MAV_BATTERY_TYPE_LIFE = 2,
3845 #[doc = "Lithium-ION battery"]
3846 MAV_BATTERY_TYPE_LION = 3,
3847 #[doc = "Nickel metal hydride battery"]
3848 MAV_BATTERY_TYPE_NIMH = 4,
3849}
3850impl MavBatteryType {
3851 pub const DEFAULT: Self = Self::MAV_BATTERY_TYPE_UNKNOWN;
3852}
3853impl Default for MavBatteryType {
3854 fn default() -> Self {
3855 Self::DEFAULT
3856 }
3857}
3858#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3859#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3860#[cfg_attr(feature = "serde", serde(tag = "type"))]
3861#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3862#[repr(u32)]
3863pub enum MavOdidClassificationType {
3864 #[doc = "The classification type for the UA is undeclared."]
3865 MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED = 0,
3866 #[doc = "The classification type for the UA follows EU (European Union) specifications."]
3867 MAV_ODID_CLASSIFICATION_TYPE_EU = 1,
3868}
3869impl MavOdidClassificationType {
3870 pub const DEFAULT: Self = Self::MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED;
3871}
3872impl Default for MavOdidClassificationType {
3873 fn default() -> Self {
3874 Self::DEFAULT
3875 }
3876}
3877#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3878#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3879#[cfg_attr(feature = "serde", serde(tag = "type"))]
3880#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3881#[repr(u32)]
3882#[doc = "Coordinate frames used by MAVLink. Not all frames are supported by all commands, messages, or vehicles. Global frames use the following naming conventions: - \"GLOBAL\": Global coordinate frame with WGS84 latitude/longitude and altitude positive over mean sea level (MSL) by default. The following modifiers may be used with \"GLOBAL\": - \"RELATIVE_ALT\": Altitude is relative to the vehicle home position rather than MSL. - \"TERRAIN_ALT\": Altitude is relative to ground level rather than MSL. - \"INT\": Latitude/longitude (in degrees) are scaled by multiplying by 1E7. Local frames use the following naming conventions: - \"LOCAL\": Origin of local frame is fixed relative to earth. Unless otherwise specified this origin is the origin of the vehicle position-estimator (\"EKF\"). - \"BODY\": Origin of local frame travels with the vehicle. NOTE, \"BODY\" does NOT indicate alignment of frame axis with vehicle attitude. - \"OFFSET\": Deprecated synonym for \"BODY\" (origin travels with the vehicle). Not to be used for new frames. Some deprecated frames do not follow these conventions (e.g. MAV_FRAME_BODY_NED and MAV_FRAME_BODY_OFFSET_NED)."]
3883pub enum MavFrame {
3884 #[doc = "Global (WGS84) coordinate frame + altitude relative to mean sea level (MSL)."]
3885 MAV_FRAME_GLOBAL = 0,
3886 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin fixed relative to earth."]
3887 MAV_FRAME_LOCAL_NED = 1,
3888 #[doc = "NOT a coordinate frame, indicates a mission command."]
3889 MAV_FRAME_MISSION = 2,
3890 #[doc = "Global (WGS84) coordinate frame + altitude relative to the home position."]
3891 MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
3892 #[doc = "ENU local tangent frame (x: East, y: North, z: Up) with origin fixed relative to earth."]
3893 MAV_FRAME_LOCAL_ENU = 4,
3894 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to mean sea level (MSL)."]
3895 MAV_FRAME_GLOBAL_INT = 5,
3896 #[doc = "Global (WGS84) coordinate frame (scaled) + altitude relative to the home position."]
3897 MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6,
3898 #[doc = "NED local tangent frame (x: North, y: East, z: Down) with origin that travels with the vehicle."]
3899 MAV_FRAME_LOCAL_OFFSET_NED = 7,
3900 #[doc = "Same as MAV_FRAME_LOCAL_NED when used to represent position values. Same as MAV_FRAME_BODY_FRD when used with velocity/acceleration values."]
3901 MAV_FRAME_BODY_NED = 8,
3902 #[doc = "This is the same as MAV_FRAME_BODY_FRD."]
3903 MAV_FRAME_BODY_OFFSET_NED = 9,
3904 #[doc = "Global (WGS84) coordinate frame with AGL altitude (altitude at ground level)."]
3905 MAV_FRAME_GLOBAL_TERRAIN_ALT = 10,
3906 #[doc = "Global (WGS84) coordinate frame (scaled) with AGL altitude (altitude at ground level)."]
3907 MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11,
3908 #[doc = "FRD local frame aligned to the vehicle's attitude (x: Forward, y: Right, z: Down) with an origin that travels with vehicle."]
3909 MAV_FRAME_BODY_FRD = 12,
3910 #[doc = "MAV_FRAME_BODY_FLU - Body fixed frame of reference, Z-up (x: Forward, y: Left, z: Up)."]
3911 MAV_FRAME_RESERVED_13 = 13,
3912 #[doc = "MAV_FRAME_MOCAP_NED - Odometry local coordinate frame of data given by a motion capture system, Z-down (x: North, y: East, z: Down)."]
3913 MAV_FRAME_RESERVED_14 = 14,
3914 #[doc = "MAV_FRAME_MOCAP_ENU - Odometry local coordinate frame of data given by a motion capture system, Z-up (x: East, y: North, z: Up)."]
3915 MAV_FRAME_RESERVED_15 = 15,
3916 #[doc = "MAV_FRAME_VISION_NED - Odometry local coordinate frame of data given by a vision estimation system, Z-down (x: North, y: East, z: Down)."]
3917 MAV_FRAME_RESERVED_16 = 16,
3918 #[doc = "MAV_FRAME_VISION_ENU - Odometry local coordinate frame of data given by a vision estimation system, Z-up (x: East, y: North, z: Up)."]
3919 MAV_FRAME_RESERVED_17 = 17,
3920 #[doc = "MAV_FRAME_ESTIM_NED - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-down (x: North, y: East, z: Down)."]
3921 MAV_FRAME_RESERVED_18 = 18,
3922 #[doc = "MAV_FRAME_ESTIM_ENU - Odometry local coordinate frame of data given by an estimator running onboard the vehicle, Z-up (x: East, y: North, z: Up)."]
3923 MAV_FRAME_RESERVED_19 = 19,
3924 #[doc = "FRD local tangent frame (x: Forward, y: Right, z: Down) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
3925 MAV_FRAME_LOCAL_FRD = 20,
3926 #[doc = "FLU local tangent frame (x: Forward, y: Left, z: Up) with origin fixed relative to earth. The forward axis is aligned to the front of the vehicle in the horizontal plane."]
3927 MAV_FRAME_LOCAL_FLU = 21,
3928}
3929impl MavFrame {
3930 pub const DEFAULT: Self = Self::MAV_FRAME_GLOBAL;
3931}
3932impl Default for MavFrame {
3933 fn default() -> Self {
3934 Self::DEFAULT
3935 }
3936}
3937#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3938#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3939#[cfg_attr(feature = "serde", serde(tag = "type"))]
3940#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3941#[repr(u32)]
3942#[doc = "Camera Modes."]
3943pub enum CameraMode {
3944 #[doc = "Camera is in image/photo capture mode."]
3945 CAMERA_MODE_IMAGE = 0,
3946 #[doc = "Camera is in video capture mode."]
3947 CAMERA_MODE_VIDEO = 1,
3948 #[doc = "Camera is in image survey capture mode. It allows for camera controller to do specific settings for surveys."]
3949 CAMERA_MODE_IMAGE_SURVEY = 2,
3950}
3951impl CameraMode {
3952 pub const DEFAULT: Self = Self::CAMERA_MODE_IMAGE;
3953}
3954impl Default for CameraMode {
3955 fn default() -> Self {
3956 Self::DEFAULT
3957 }
3958}
3959#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3960#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3961#[cfg_attr(feature = "serde", serde(tag = "type"))]
3962#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3963#[repr(u32)]
3964#[doc = "Actuator configuration, used to change a setting on an actuator. Component information metadata can be used to know which outputs support which commands."]
3965pub enum ActuatorConfiguration {
3966 #[doc = "Do nothing."]
3967 ACTUATOR_CONFIGURATION_NONE = 0,
3968 #[doc = "Command the actuator to beep now."]
3969 ACTUATOR_CONFIGURATION_BEEP = 1,
3970 #[doc = "Permanently set the actuator (ESC) to 3D mode (reversible thrust)."]
3971 ACTUATOR_CONFIGURATION_3D_MODE_ON = 2,
3972 #[doc = "Permanently set the actuator (ESC) to non 3D mode (non-reversible thrust)."]
3973 ACTUATOR_CONFIGURATION_3D_MODE_OFF = 3,
3974 #[doc = "Permanently set the actuator (ESC) to spin direction 1 (which can be clockwise or counter-clockwise)."]
3975 ACTUATOR_CONFIGURATION_SPIN_DIRECTION1 = 4,
3976 #[doc = "Permanently set the actuator (ESC) to spin direction 2 (opposite of direction 1)."]
3977 ACTUATOR_CONFIGURATION_SPIN_DIRECTION2 = 5,
3978}
3979impl ActuatorConfiguration {
3980 pub const DEFAULT: Self = Self::ACTUATOR_CONFIGURATION_NONE;
3981}
3982impl Default for ActuatorConfiguration {
3983 fn default() -> Self {
3984 Self::DEFAULT
3985 }
3986}
3987#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
3988#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
3989#[cfg_attr(feature = "serde", serde(tag = "type"))]
3990#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
3991#[repr(u32)]
3992#[doc = "Direction of VTOL transition"]
3993pub enum VtolTransitionHeading {
3994 #[doc = "Respect the heading configuration of the vehicle."]
3995 VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT = 0,
3996 #[doc = "Use the heading pointing towards the next waypoint."]
3997 VTOL_TRANSITION_HEADING_NEXT_WAYPOINT = 1,
3998 #[doc = "Use the heading on takeoff (while sitting on the ground)."]
3999 VTOL_TRANSITION_HEADING_TAKEOFF = 2,
4000 #[doc = "Use the specified heading in parameter 4."]
4001 VTOL_TRANSITION_HEADING_SPECIFIED = 3,
4002 #[doc = "Use the current heading when reaching takeoff altitude (potentially facing the wind when weather-vaning is active)."]
4003 VTOL_TRANSITION_HEADING_ANY = 4,
4004}
4005impl VtolTransitionHeading {
4006 pub const DEFAULT: Self = Self::VTOL_TRANSITION_HEADING_VEHICLE_DEFAULT;
4007}
4008impl Default for VtolTransitionHeading {
4009 fn default() -> Self {
4010 Self::DEFAULT
4011 }
4012}
4013#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4014#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4015#[cfg_attr(feature = "serde", serde(tag = "type"))]
4016#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4017#[repr(u32)]
4018pub enum FenceBreach {
4019 #[doc = "No last fence breach"]
4020 FENCE_BREACH_NONE = 0,
4021 #[doc = "Breached minimum altitude"]
4022 FENCE_BREACH_MINALT = 1,
4023 #[doc = "Breached maximum altitude"]
4024 FENCE_BREACH_MAXALT = 2,
4025 #[doc = "Breached fence boundary"]
4026 FENCE_BREACH_BOUNDARY = 3,
4027}
4028impl FenceBreach {
4029 pub const DEFAULT: Self = Self::FENCE_BREACH_NONE;
4030}
4031impl Default for FenceBreach {
4032 fn default() -> Self {
4033 Self::DEFAULT
4034 }
4035}
4036#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4037#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4038#[cfg_attr(feature = "serde", serde(tag = "type"))]
4039#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4040#[repr(u32)]
4041#[doc = "Reason for an event error response."]
4042pub enum MavEventErrorReason {
4043 #[doc = "The requested event is not available (anymore)."]
4044 MAV_EVENT_ERROR_REASON_UNAVAILABLE = 0,
4045}
4046impl MavEventErrorReason {
4047 pub const DEFAULT: Self = Self::MAV_EVENT_ERROR_REASON_UNAVAILABLE;
4048}
4049impl Default for MavEventErrorReason {
4050 fn default() -> Self {
4051 Self::DEFAULT
4052 }
4053}
4054#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4055#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4056#[cfg_attr(feature = "serde", serde(tag = "type"))]
4057#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4058#[repr(u32)]
4059#[doc = "RC type. Used in MAV_CMD_START_RX_PAIR."]
4060pub enum RcType {
4061 #[doc = "Spektrum"]
4062 RC_TYPE_SPEKTRUM = 0,
4063 #[doc = "CRSF"]
4064 RC_TYPE_CRSF = 1,
4065}
4066impl RcType {
4067 pub const DEFAULT: Self = Self::RC_TYPE_SPEKTRUM;
4068}
4069impl Default for RcType {
4070 fn default() -> Self {
4071 Self::DEFAULT
4072 }
4073}
4074#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4075#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4076#[cfg_attr(feature = "serde", serde(tag = "type"))]
4077#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4078#[repr(u32)]
4079#[doc = "Status for ADS-B transponder dynamic input"]
4080pub enum UavionixAdsbOutDynamicGpsFix {
4081 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0 = 0,
4082 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_1 = 1,
4083 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_2D = 2,
4084 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_3D = 3,
4085 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_DGPS = 4,
4086 UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_RTK = 5,
4087}
4088impl UavionixAdsbOutDynamicGpsFix {
4089 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_DYNAMIC_GPS_FIX_NONE_0;
4090}
4091impl Default for UavionixAdsbOutDynamicGpsFix {
4092 fn default() -> Self {
4093 Self::DEFAULT
4094 }
4095}
4096#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4097#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4098#[cfg_attr(feature = "serde", serde(tag = "type"))]
4099#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4100#[repr(u32)]
4101#[doc = "Defines how throttle value is represented in MAV_CMD_DO_MOTOR_TEST."]
4102pub enum MotorTestThrottleType {
4103 #[doc = "Throttle as a percentage (0 ~ 100)"]
4104 MOTOR_TEST_THROTTLE_PERCENT = 0,
4105 #[doc = "Throttle as an absolute PWM value (normally in range of 1000~2000)."]
4106 MOTOR_TEST_THROTTLE_PWM = 1,
4107 #[doc = "Throttle pass-through from pilot's transmitter."]
4108 MOTOR_TEST_THROTTLE_PILOT = 2,
4109 #[doc = "Per-motor compass calibration test."]
4110 MOTOR_TEST_COMPASS_CAL = 3,
4111}
4112impl MotorTestThrottleType {
4113 pub const DEFAULT: Self = Self::MOTOR_TEST_THROTTLE_PERCENT;
4114}
4115impl Default for MotorTestThrottleType {
4116 fn default() -> Self {
4117 Self::DEFAULT
4118 }
4119}
4120bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder dynamic report"] pub struct UavionixAdsbOutDynamicState : u16 { const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE = 1 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_AUTOPILOT_ENABLED = 2 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_NICBARO_CROSSCHECKED = 4 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND = 8 ; const UAVIONIX_ADSB_OUT_DYNAMIC_STATE_IDENT = 16 ; } }
4121impl UavionixAdsbOutDynamicState {
4122 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_DYNAMIC_STATE_INTENT_CHANGE;
4123}
4124impl Default for UavionixAdsbOutDynamicState {
4125 fn default() -> Self {
4126 Self::DEFAULT
4127 }
4128}
4129bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Camera capability flags (Bitmap)"] pub struct CameraCapFlags : u32 { # [doc = "Camera is able to record video"] const CAMERA_CAP_FLAGS_CAPTURE_VIDEO = 1 ; # [doc = "Camera is able to capture images"] const CAMERA_CAP_FLAGS_CAPTURE_IMAGE = 2 ; # [doc = "Camera has separate Video and Image/Photo modes (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_MODES = 4 ; # [doc = "Camera can capture images while in video mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_IMAGE_IN_VIDEO_MODE = 8 ; # [doc = "Camera can capture videos while in Photo/Image mode"] const CAMERA_CAP_FLAGS_CAN_CAPTURE_VIDEO_IN_IMAGE_MODE = 16 ; # [doc = "Camera has image survey mode (MAV_CMD_SET_CAMERA_MODE)"] const CAMERA_CAP_FLAGS_HAS_IMAGE_SURVEY_MODE = 32 ; # [doc = "Camera has basic zoom control (MAV_CMD_SET_CAMERA_ZOOM)"] const CAMERA_CAP_FLAGS_HAS_BASIC_ZOOM = 64 ; # [doc = "Camera has basic focus control (MAV_CMD_SET_CAMERA_FOCUS)"] const CAMERA_CAP_FLAGS_HAS_BASIC_FOCUS = 128 ; # [doc = "Camera has video streaming capabilities (request VIDEO_STREAM_INFORMATION with MAV_CMD_REQUEST_MESSAGE for video streaming info)"] const CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM = 256 ; # [doc = "Camera supports tracking of a point on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_POINT = 512 ; # [doc = "Camera supports tracking of a selection rectangle on the camera view."] const CAMERA_CAP_FLAGS_HAS_TRACKING_RECTANGLE = 1024 ; # [doc = "Camera supports tracking geo status (CAMERA_TRACKING_GEO_STATUS)."] const CAMERA_CAP_FLAGS_HAS_TRACKING_GEO_STATUS = 2048 ; # [doc = "Camera supports absolute thermal range (request CAMERA_THERMAL_RANGE with MAV_CMD_REQUEST_MESSAGE)."] const CAMERA_CAP_FLAGS_HAS_THERMAL_RANGE = 4096 ; } }
4130impl CameraCapFlags {
4131 pub const DEFAULT: Self = Self::CAMERA_CAP_FLAGS_CAPTURE_VIDEO;
4132}
4133impl Default for CameraCapFlags {
4134 fn default() -> Self {
4135 Self::DEFAULT
4136 }
4137}
4138#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4139#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4140#[cfg_attr(feature = "serde", serde(tag = "type"))]
4141#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4142#[repr(u32)]
4143#[doc = "Component ids (values) for the different types and instances of onboard hardware/software that might make up a MAVLink system (autopilot, cameras, servos, GPS systems, avoidance systems etc.). Components must use the appropriate ID in their source address when sending messages. Components can also use IDs to determine if they are the intended recipient of an incoming message. The MAV_COMP_ID_ALL value is used to indicate messages that must be processed by all components. When creating new entries, components that can have multiple instances (e.g. cameras, servos etc.) should be allocated sequential values. An appropriate number of values should be left free after these components to allow the number of instances to be expanded."]
4144pub enum MavComponent {
4145 #[doc = "Target id (target_component) used to broadcast messages to all components of the receiving system. Components should attempt to process messages with this component ID and forward to components on any other interfaces. Note: This is not a valid *source* component id for a message."]
4146 MAV_COMP_ID_ALL = 0,
4147 #[doc = "System flight controller component (\"autopilot\"). Only one autopilot is expected in a particular system."]
4148 MAV_COMP_ID_AUTOPILOT1 = 1,
4149 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4150 MAV_COMP_ID_USER1 = 25,
4151 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4152 MAV_COMP_ID_USER2 = 26,
4153 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4154 MAV_COMP_ID_USER3 = 27,
4155 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4156 MAV_COMP_ID_USER4 = 28,
4157 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4158 MAV_COMP_ID_USER5 = 29,
4159 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4160 MAV_COMP_ID_USER6 = 30,
4161 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4162 MAV_COMP_ID_USER7 = 31,
4163 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4164 MAV_COMP_ID_USER8 = 32,
4165 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4166 MAV_COMP_ID_USER9 = 33,
4167 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4168 MAV_COMP_ID_USER10 = 34,
4169 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4170 MAV_COMP_ID_USER11 = 35,
4171 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4172 MAV_COMP_ID_USER12 = 36,
4173 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4174 MAV_COMP_ID_USER13 = 37,
4175 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4176 MAV_COMP_ID_USER14 = 38,
4177 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4178 MAV_COMP_ID_USER15 = 39,
4179 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4180 MAV_COMP_ID_USER16 = 40,
4181 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4182 MAV_COMP_ID_USER17 = 41,
4183 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4184 MAV_COMP_ID_USER18 = 42,
4185 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4186 MAV_COMP_ID_USER19 = 43,
4187 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4188 MAV_COMP_ID_USER20 = 44,
4189 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4190 MAV_COMP_ID_USER21 = 45,
4191 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4192 MAV_COMP_ID_USER22 = 46,
4193 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4194 MAV_COMP_ID_USER23 = 47,
4195 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4196 MAV_COMP_ID_USER24 = 48,
4197 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4198 MAV_COMP_ID_USER25 = 49,
4199 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4200 MAV_COMP_ID_USER26 = 50,
4201 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4202 MAV_COMP_ID_USER27 = 51,
4203 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4204 MAV_COMP_ID_USER28 = 52,
4205 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4206 MAV_COMP_ID_USER29 = 53,
4207 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4208 MAV_COMP_ID_USER30 = 54,
4209 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4210 MAV_COMP_ID_USER31 = 55,
4211 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4212 MAV_COMP_ID_USER32 = 56,
4213 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4214 MAV_COMP_ID_USER33 = 57,
4215 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4216 MAV_COMP_ID_USER34 = 58,
4217 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4218 MAV_COMP_ID_USER35 = 59,
4219 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4220 MAV_COMP_ID_USER36 = 60,
4221 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4222 MAV_COMP_ID_USER37 = 61,
4223 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4224 MAV_COMP_ID_USER38 = 62,
4225 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4226 MAV_COMP_ID_USER39 = 63,
4227 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4228 MAV_COMP_ID_USER40 = 64,
4229 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4230 MAV_COMP_ID_USER41 = 65,
4231 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4232 MAV_COMP_ID_USER42 = 66,
4233 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4234 MAV_COMP_ID_USER43 = 67,
4235 #[doc = "Telemetry radio (e.g. SiK radio, or other component that emits RADIO_STATUS messages)."]
4236 MAV_COMP_ID_TELEMETRY_RADIO = 68,
4237 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4238 MAV_COMP_ID_USER45 = 69,
4239 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4240 MAV_COMP_ID_USER46 = 70,
4241 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4242 MAV_COMP_ID_USER47 = 71,
4243 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4244 MAV_COMP_ID_USER48 = 72,
4245 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4246 MAV_COMP_ID_USER49 = 73,
4247 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4248 MAV_COMP_ID_USER50 = 74,
4249 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4250 MAV_COMP_ID_USER51 = 75,
4251 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4252 MAV_COMP_ID_USER52 = 76,
4253 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4254 MAV_COMP_ID_USER53 = 77,
4255 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4256 MAV_COMP_ID_USER54 = 78,
4257 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4258 MAV_COMP_ID_USER55 = 79,
4259 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4260 MAV_COMP_ID_USER56 = 80,
4261 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4262 MAV_COMP_ID_USER57 = 81,
4263 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4264 MAV_COMP_ID_USER58 = 82,
4265 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4266 MAV_COMP_ID_USER59 = 83,
4267 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4268 MAV_COMP_ID_USER60 = 84,
4269 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4270 MAV_COMP_ID_USER61 = 85,
4271 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4272 MAV_COMP_ID_USER62 = 86,
4273 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4274 MAV_COMP_ID_USER63 = 87,
4275 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4276 MAV_COMP_ID_USER64 = 88,
4277 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4278 MAV_COMP_ID_USER65 = 89,
4279 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4280 MAV_COMP_ID_USER66 = 90,
4281 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4282 MAV_COMP_ID_USER67 = 91,
4283 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4284 MAV_COMP_ID_USER68 = 92,
4285 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4286 MAV_COMP_ID_USER69 = 93,
4287 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4288 MAV_COMP_ID_USER70 = 94,
4289 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4290 MAV_COMP_ID_USER71 = 95,
4291 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4292 MAV_COMP_ID_USER72 = 96,
4293 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4294 MAV_COMP_ID_USER73 = 97,
4295 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4296 MAV_COMP_ID_USER74 = 98,
4297 #[doc = "Id for a component on privately managed MAVLink network. Can be used for any purpose but may not be published by components outside of the private network."]
4298 MAV_COMP_ID_USER75 = 99,
4299 #[doc = "Camera #1."]
4300 MAV_COMP_ID_CAMERA = 100,
4301 #[doc = "Camera #2."]
4302 MAV_COMP_ID_CAMERA2 = 101,
4303 #[doc = "Camera #3."]
4304 MAV_COMP_ID_CAMERA3 = 102,
4305 #[doc = "Camera #4."]
4306 MAV_COMP_ID_CAMERA4 = 103,
4307 #[doc = "Camera #5."]
4308 MAV_COMP_ID_CAMERA5 = 104,
4309 #[doc = "Camera #6."]
4310 MAV_COMP_ID_CAMERA6 = 105,
4311 #[doc = "Servo #1."]
4312 MAV_COMP_ID_SERVO1 = 140,
4313 #[doc = "Servo #2."]
4314 MAV_COMP_ID_SERVO2 = 141,
4315 #[doc = "Servo #3."]
4316 MAV_COMP_ID_SERVO3 = 142,
4317 #[doc = "Servo #4."]
4318 MAV_COMP_ID_SERVO4 = 143,
4319 #[doc = "Servo #5."]
4320 MAV_COMP_ID_SERVO5 = 144,
4321 #[doc = "Servo #6."]
4322 MAV_COMP_ID_SERVO6 = 145,
4323 #[doc = "Servo #7."]
4324 MAV_COMP_ID_SERVO7 = 146,
4325 #[doc = "Servo #8."]
4326 MAV_COMP_ID_SERVO8 = 147,
4327 #[doc = "Servo #9."]
4328 MAV_COMP_ID_SERVO9 = 148,
4329 #[doc = "Servo #10."]
4330 MAV_COMP_ID_SERVO10 = 149,
4331 #[doc = "Servo #11."]
4332 MAV_COMP_ID_SERVO11 = 150,
4333 #[doc = "Servo #12."]
4334 MAV_COMP_ID_SERVO12 = 151,
4335 #[doc = "Servo #13."]
4336 MAV_COMP_ID_SERVO13 = 152,
4337 #[doc = "Servo #14."]
4338 MAV_COMP_ID_SERVO14 = 153,
4339 #[doc = "Gimbal #1."]
4340 MAV_COMP_ID_GIMBAL = 154,
4341 #[doc = "Logging component."]
4342 MAV_COMP_ID_LOG = 155,
4343 #[doc = "Automatic Dependent Surveillance-Broadcast (ADS-B) component."]
4344 MAV_COMP_ID_ADSB = 156,
4345 #[doc = "On Screen Display (OSD) devices for video links."]
4346 MAV_COMP_ID_OSD = 157,
4347 #[doc = "Generic autopilot peripheral component ID. Meant for devices that do not implement the parameter microservice."]
4348 MAV_COMP_ID_PERIPHERAL = 158,
4349 #[doc = "Gimbal ID for QX1."]
4350 MAV_COMP_ID_QX1_GIMBAL = 159,
4351 #[doc = "FLARM collision alert component."]
4352 MAV_COMP_ID_FLARM = 160,
4353 #[doc = "Parachute component."]
4354 MAV_COMP_ID_PARACHUTE = 161,
4355 #[doc = "Winch component."]
4356 MAV_COMP_ID_WINCH = 169,
4357 #[doc = "Gimbal #2."]
4358 MAV_COMP_ID_GIMBAL2 = 171,
4359 #[doc = "Gimbal #3."]
4360 MAV_COMP_ID_GIMBAL3 = 172,
4361 #[doc = "Gimbal #4"]
4362 MAV_COMP_ID_GIMBAL4 = 173,
4363 #[doc = "Gimbal #5."]
4364 MAV_COMP_ID_GIMBAL5 = 174,
4365 #[doc = "Gimbal #6."]
4366 MAV_COMP_ID_GIMBAL6 = 175,
4367 #[doc = "Battery #1."]
4368 MAV_COMP_ID_BATTERY = 180,
4369 #[doc = "Battery #2."]
4370 MAV_COMP_ID_BATTERY2 = 181,
4371 #[doc = "CAN over MAVLink client."]
4372 MAV_COMP_ID_MAVCAN = 189,
4373 #[doc = "Component that can generate/supply a mission flight plan (e.g. GCS or developer API)."]
4374 MAV_COMP_ID_MISSIONPLANNER = 190,
4375 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
4376 MAV_COMP_ID_ONBOARD_COMPUTER = 191,
4377 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
4378 MAV_COMP_ID_ONBOARD_COMPUTER2 = 192,
4379 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
4380 MAV_COMP_ID_ONBOARD_COMPUTER3 = 193,
4381 #[doc = "Component that lives on the onboard computer (companion computer) and has some generic functionalities, such as settings system parameters and monitoring the status of some processes that don't directly speak mavlink and so on."]
4382 MAV_COMP_ID_ONBOARD_COMPUTER4 = 194,
4383 #[doc = "Component that finds an optimal path between points based on a certain constraint (e.g. minimum snap, shortest path, cost, etc.)."]
4384 MAV_COMP_ID_PATHPLANNER = 195,
4385 #[doc = "Component that plans a collision free path between two points."]
4386 MAV_COMP_ID_OBSTACLE_AVOIDANCE = 196,
4387 #[doc = "Component that provides position estimates using VIO techniques."]
4388 MAV_COMP_ID_VISUAL_INERTIAL_ODOMETRY = 197,
4389 #[doc = "Component that manages pairing of vehicle and GCS."]
4390 MAV_COMP_ID_PAIRING_MANAGER = 198,
4391 #[doc = "Inertial Measurement Unit (IMU) #1."]
4392 MAV_COMP_ID_IMU = 200,
4393 #[doc = "Inertial Measurement Unit (IMU) #2."]
4394 MAV_COMP_ID_IMU_2 = 201,
4395 #[doc = "Inertial Measurement Unit (IMU) #3."]
4396 MAV_COMP_ID_IMU_3 = 202,
4397 #[doc = "GPS #1."]
4398 MAV_COMP_ID_GPS = 220,
4399 #[doc = "GPS #2."]
4400 MAV_COMP_ID_GPS2 = 221,
4401 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
4402 MAV_COMP_ID_ODID_TXRX_1 = 236,
4403 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
4404 MAV_COMP_ID_ODID_TXRX_2 = 237,
4405 #[doc = "Open Drone ID transmitter/receiver (Bluetooth/WiFi/Internet)."]
4406 MAV_COMP_ID_ODID_TXRX_3 = 238,
4407 #[doc = "Component to bridge MAVLink to UDP (i.e. from a UART)."]
4408 MAV_COMP_ID_UDP_BRIDGE = 240,
4409 #[doc = "Component to bridge to UART (i.e. from UDP)."]
4410 MAV_COMP_ID_UART_BRIDGE = 241,
4411 #[doc = "Component handling TUNNEL messages (e.g. vendor specific GUI of a component)."]
4412 MAV_COMP_ID_TUNNEL_NODE = 242,
4413 #[doc = "Illuminator"]
4414 MAV_COMP_ID_ILLUMINATOR = 243,
4415 #[doc = "Deprecated, don't use. Component for handling system messages (e.g. to ARM, takeoff, etc.)."]
4416 MAV_COMP_ID_SYSTEM_CONTROL = 250,
4417}
4418impl MavComponent {
4419 pub const DEFAULT: Self = Self::MAV_COMP_ID_ALL;
4420}
4421impl Default for MavComponent {
4422 fn default() -> Self {
4423 Self::DEFAULT
4424 }
4425}
4426#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4427#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4428#[cfg_attr(feature = "serde", serde(tag = "type"))]
4429#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4430#[repr(u32)]
4431pub enum MavState {
4432 #[doc = "Uninitialized system, state is unknown."]
4433 MAV_STATE_UNINIT = 0,
4434 #[doc = "System is booting up."]
4435 MAV_STATE_BOOT = 1,
4436 #[doc = "System is calibrating and not flight-ready."]
4437 MAV_STATE_CALIBRATING = 2,
4438 #[doc = "System is grounded and on standby. It can be launched any time."]
4439 MAV_STATE_STANDBY = 3,
4440 #[doc = "System is active and might be already airborne. Motors are engaged."]
4441 MAV_STATE_ACTIVE = 4,
4442 #[doc = "System is in a non-normal flight mode (failsafe). It can however still navigate."]
4443 MAV_STATE_CRITICAL = 5,
4444 #[doc = "System is in a non-normal flight mode (failsafe). It lost control over parts or over the whole airframe. It is in mayday and going down."]
4445 MAV_STATE_EMERGENCY = 6,
4446 #[doc = "System just initialized its power-down sequence, will shut down now."]
4447 MAV_STATE_POWEROFF = 7,
4448 #[doc = "System is terminating itself (failsafe or commanded)."]
4449 MAV_STATE_FLIGHT_TERMINATION = 8,
4450}
4451impl MavState {
4452 pub const DEFAULT: Self = Self::MAV_STATE_UNINIT;
4453}
4454impl Default for MavState {
4455 fn default() -> Self {
4456 Self::DEFAULT
4457 }
4458}
4459bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Illuminator module error flags (bitmap, 0 means no error)"] pub struct IlluminatorErrorFlags : u32 { # [doc = "Illuminator thermal throttling error."] const ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING = 1 ; # [doc = "Illuminator over temperature shutdown error."] const ILLUMINATOR_ERROR_FLAGS_OVER_TEMPERATURE_SHUTDOWN = 2 ; # [doc = "Illuminator thermistor failure."] const ILLUMINATOR_ERROR_FLAGS_THERMISTOR_FAILURE = 4 ; } }
4460impl IlluminatorErrorFlags {
4461 pub const DEFAULT: Self = Self::ILLUMINATOR_ERROR_FLAGS_THERMAL_THROTTLING;
4462}
4463impl Default for IlluminatorErrorFlags {
4464 fn default() -> Self {
4465 Self::DEFAULT
4466 }
4467}
4468bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags for the global position report."] pub struct UtmDataAvailFlags : u8 { # [doc = "The field time contains valid data."] const UTM_DATA_AVAIL_FLAGS_TIME_VALID = 1 ; # [doc = "The field uas_id contains valid data."] const UTM_DATA_AVAIL_FLAGS_UAS_ID_AVAILABLE = 2 ; # [doc = "The fields lat, lon and h_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_POSITION_AVAILABLE = 4 ; # [doc = "The fields alt and v_acc contain valid data."] const UTM_DATA_AVAIL_FLAGS_ALTITUDE_AVAILABLE = 8 ; # [doc = "The field relative_alt contains valid data."] const UTM_DATA_AVAIL_FLAGS_RELATIVE_ALTITUDE_AVAILABLE = 16 ; # [doc = "The fields vx and vy contain valid data."] const UTM_DATA_AVAIL_FLAGS_HORIZONTAL_VELO_AVAILABLE = 32 ; # [doc = "The field vz contains valid data."] const UTM_DATA_AVAIL_FLAGS_VERTICAL_VELO_AVAILABLE = 64 ; # [doc = "The fields next_lat, next_lon and next_alt contain valid data."] const UTM_DATA_AVAIL_FLAGS_NEXT_WAYPOINT_AVAILABLE = 128 ; } }
4469impl UtmDataAvailFlags {
4470 pub const DEFAULT: Self = Self::UTM_DATA_AVAIL_FLAGS_TIME_VALID;
4471}
4472impl Default for UtmDataAvailFlags {
4473 fn default() -> Self {
4474 Self::DEFAULT
4475 }
4476}
4477#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4478#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4479#[cfg_attr(feature = "serde", serde(tag = "type"))]
4480#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4481#[repr(u32)]
4482pub enum MavOdidClassEu {
4483 #[doc = "The class for the UA, according to the EU specification, is undeclared."]
4484 MAV_ODID_CLASS_EU_UNDECLARED = 0,
4485 #[doc = "The class for the UA, according to the EU specification, is Class 0."]
4486 MAV_ODID_CLASS_EU_CLASS_0 = 1,
4487 #[doc = "The class for the UA, according to the EU specification, is Class 1."]
4488 MAV_ODID_CLASS_EU_CLASS_1 = 2,
4489 #[doc = "The class for the UA, according to the EU specification, is Class 2."]
4490 MAV_ODID_CLASS_EU_CLASS_2 = 3,
4491 #[doc = "The class for the UA, according to the EU specification, is Class 3."]
4492 MAV_ODID_CLASS_EU_CLASS_3 = 4,
4493 #[doc = "The class for the UA, according to the EU specification, is Class 4."]
4494 MAV_ODID_CLASS_EU_CLASS_4 = 5,
4495 #[doc = "The class for the UA, according to the EU specification, is Class 5."]
4496 MAV_ODID_CLASS_EU_CLASS_5 = 6,
4497 #[doc = "The class for the UA, according to the EU specification, is Class 6."]
4498 MAV_ODID_CLASS_EU_CLASS_6 = 7,
4499}
4500impl MavOdidClassEu {
4501 pub const DEFAULT: Self = Self::MAV_ODID_CLASS_EU_UNDECLARED;
4502}
4503impl Default for MavOdidClassEu {
4504 fn default() -> Self {
4505 Self::DEFAULT
4506 }
4507}
4508bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "State flags for ADS-B transponder fault report"] pub struct UavionixAdsbOutStatusFault : u8 { const UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL = 8 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_NO_POS = 16 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_GPS_UNAVAIL = 32 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_TX_SYSTEM_FAIL = 64 ; const UAVIONIX_ADSB_OUT_STATUS_FAULT_MAINT_REQ = 128 ; } }
4509impl UavionixAdsbOutStatusFault {
4510 pub const DEFAULT: Self = Self::UAVIONIX_ADSB_OUT_STATUS_FAULT_STATUS_MESSAGE_UNAVAIL;
4511}
4512impl Default for UavionixAdsbOutStatusFault {
4513 fn default() -> Self {
4514 Self::DEFAULT
4515 }
4516}
4517#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4518#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4519#[cfg_attr(feature = "serde", serde(tag = "type"))]
4520#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4521#[repr(u32)]
4522#[doc = "Result of mission operation (in a MISSION_ACK message)."]
4523pub enum MavMissionResult {
4524 #[doc = "mission accepted OK"]
4525 MAV_MISSION_ACCEPTED = 0,
4526 #[doc = "Generic error / not accepting mission commands at all right now."]
4527 MAV_MISSION_ERROR = 1,
4528 #[doc = "Coordinate frame is not supported."]
4529 MAV_MISSION_UNSUPPORTED_FRAME = 2,
4530 #[doc = "Command is not supported."]
4531 MAV_MISSION_UNSUPPORTED = 3,
4532 #[doc = "Mission items exceed storage space."]
4533 MAV_MISSION_NO_SPACE = 4,
4534 #[doc = "One of the parameters has an invalid value."]
4535 MAV_MISSION_INVALID = 5,
4536 #[doc = "param1 has an invalid value."]
4537 MAV_MISSION_INVALID_PARAM1 = 6,
4538 #[doc = "param2 has an invalid value."]
4539 MAV_MISSION_INVALID_PARAM2 = 7,
4540 #[doc = "param3 has an invalid value."]
4541 MAV_MISSION_INVALID_PARAM3 = 8,
4542 #[doc = "param4 has an invalid value."]
4543 MAV_MISSION_INVALID_PARAM4 = 9,
4544 #[doc = "x / param5 has an invalid value."]
4545 MAV_MISSION_INVALID_PARAM5_X = 10,
4546 #[doc = "y / param6 has an invalid value."]
4547 MAV_MISSION_INVALID_PARAM6_Y = 11,
4548 #[doc = "z / param7 has an invalid value."]
4549 MAV_MISSION_INVALID_PARAM7 = 12,
4550 #[doc = "Mission item received out of sequence"]
4551 MAV_MISSION_INVALID_SEQUENCE = 13,
4552 #[doc = "Not accepting any mission commands from this communication partner."]
4553 MAV_MISSION_DENIED = 14,
4554 #[doc = "Current mission operation cancelled (e.g. mission upload, mission download)."]
4555 MAV_MISSION_OPERATION_CANCELLED = 15,
4556}
4557impl MavMissionResult {
4558 pub const DEFAULT: Self = Self::MAV_MISSION_ACCEPTED;
4559}
4560impl Default for MavMissionResult {
4561 fn default() -> Self {
4562 Self::DEFAULT
4563 }
4564}
4565#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4566#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4567#[cfg_attr(feature = "serde", serde(tag = "type"))]
4568#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4569#[repr(u32)]
4570pub enum MavOdidIdType {
4571 #[doc = "No type defined."]
4572 MAV_ODID_ID_TYPE_NONE = 0,
4573 #[doc = "Manufacturer Serial Number (ANSI/CTA-2063 format)."]
4574 MAV_ODID_ID_TYPE_SERIAL_NUMBER = 1,
4575 #[doc = "CAA (Civil Aviation Authority) registered ID. Format: [ICAO Country Code].[CAA Assigned ID]."]
4576 MAV_ODID_ID_TYPE_CAA_REGISTRATION_ID = 2,
4577 #[doc = "UTM (Unmanned Traffic Management) assigned UUID (RFC4122)."]
4578 MAV_ODID_ID_TYPE_UTM_ASSIGNED_UUID = 3,
4579 #[doc = "A 20 byte ID for a specific flight/session. The exact ID type is indicated by the first byte of uas_id and these type values are managed by ICAO."]
4580 MAV_ODID_ID_TYPE_SPECIFIC_SESSION_ID = 4,
4581}
4582impl MavOdidIdType {
4583 pub const DEFAULT: Self = Self::MAV_ODID_ID_TYPE_NONE;
4584}
4585impl Default for MavOdidIdType {
4586 fn default() -> Self {
4587 Self::DEFAULT
4588 }
4589}
4590bitflags! { # [cfg_attr (feature = "serde" , derive (Serialize , Deserialize))] # [cfg_attr (feature = "arbitrary" , derive (Arbitrary))] # [derive (Debug , Copy , Clone , PartialEq)] # [doc = "Flags to report ESC failures."] pub struct EscFailureFlags : u16 { # [doc = "Over current failure."] const ESC_FAILURE_OVER_CURRENT = 1 ; # [doc = "Over voltage failure."] const ESC_FAILURE_OVER_VOLTAGE = 2 ; # [doc = "Over temperature failure."] const ESC_FAILURE_OVER_TEMPERATURE = 4 ; # [doc = "Over RPM failure."] const ESC_FAILURE_OVER_RPM = 8 ; # [doc = "Inconsistent command failure i.e. out of bounds."] const ESC_FAILURE_INCONSISTENT_CMD = 16 ; # [doc = "Motor stuck failure."] const ESC_FAILURE_MOTOR_STUCK = 32 ; # [doc = "Generic ESC failure."] const ESC_FAILURE_GENERIC = 64 ; } }
4591impl EscFailureFlags {
4592 pub const DEFAULT: Self = Self::ESC_FAILURE_OVER_CURRENT;
4593}
4594impl Default for EscFailureFlags {
4595 fn default() -> Self {
4596 Self::DEFAULT
4597 }
4598}
4599#[derive(Debug, Copy, Clone, PartialEq, FromPrimitive, ToPrimitive)]
4600#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4601#[cfg_attr(feature = "serde", serde(tag = "type"))]
4602#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4603#[repr(u32)]
4604#[doc = "Camera tracking modes"]
4605pub enum CameraTrackingMode {
4606 #[doc = "Not tracking"]
4607 CAMERA_TRACKING_MODE_NONE = 0,
4608 #[doc = "Target is a point"]
4609 CAMERA_TRACKING_MODE_POINT = 1,
4610 #[doc = "Target is a rectangle"]
4611 CAMERA_TRACKING_MODE_RECTANGLE = 2,
4612}
4613impl CameraTrackingMode {
4614 pub const DEFAULT: Self = Self::CAMERA_TRACKING_MODE_NONE;
4615}
4616impl Default for CameraTrackingMode {
4617 fn default() -> Self {
4618 Self::DEFAULT
4619 }
4620}
4621#[doc = "id: 44"]
4622#[doc = "This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of waypoints."]
4623#[derive(Debug, Clone, PartialEq)]
4624#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4625#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4626pub struct MISSION_COUNT_DATA {
4627 #[doc = "Number of mission items in the sequence"]
4628 pub count: u16,
4629 #[doc = "System ID"]
4630 pub target_system: u8,
4631 #[doc = "Component ID"]
4632 pub target_component: u8,
4633 #[doc = "Mission type."]
4634 #[cfg_attr(feature = "serde", serde(default))]
4635 pub mission_type: MavMissionType,
4636 #[doc = "Id of current on-vehicle mission, fence, or rally point plan (on download from vehicle). This field is used when downloading a plan from a vehicle to a GCS. 0 on upload to the vehicle from GCS. 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded. The ids are recalculated by the vehicle when any part of the on-vehicle plan changes (when a new plan is uploaded, the vehicle returns the new id to the GCS in MISSION_ACK)."]
4637 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
4638 pub opaque_id: u32,
4639}
4640impl MISSION_COUNT_DATA {
4641 pub const ENCODED_LEN: usize = 9usize;
4642 pub const DEFAULT: Self = Self {
4643 count: 0_u16,
4644 target_system: 0_u8,
4645 target_component: 0_u8,
4646 mission_type: MavMissionType::DEFAULT,
4647 opaque_id: 0_u32,
4648 };
4649 #[cfg(feature = "arbitrary")]
4650 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4651 use arbitrary::{Arbitrary, Unstructured};
4652 let mut buf = [0u8; 1024];
4653 rng.fill_bytes(&mut buf);
4654 let mut unstructured = Unstructured::new(&buf);
4655 Self::arbitrary(&mut unstructured).unwrap_or_default()
4656 }
4657}
4658impl Default for MISSION_COUNT_DATA {
4659 fn default() -> Self {
4660 Self::DEFAULT.clone()
4661 }
4662}
4663impl MessageData for MISSION_COUNT_DATA {
4664 type Message = MavMessage;
4665 const ID: u32 = 44u32;
4666 const NAME: &'static str = "MISSION_COUNT";
4667 const EXTRA_CRC: u8 = 221u8;
4668 const ENCODED_LEN: usize = 9usize;
4669 fn deser(
4670 _version: MavlinkVersion,
4671 __input: &[u8],
4672 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4673 let avail_len = __input.len();
4674 let mut payload_buf = [0; Self::ENCODED_LEN];
4675 let mut buf = if avail_len < Self::ENCODED_LEN {
4676 payload_buf[0..avail_len].copy_from_slice(__input);
4677 Bytes::new(&payload_buf)
4678 } else {
4679 Bytes::new(__input)
4680 };
4681 let mut __struct = Self::default();
4682 __struct.count = buf.get_u16_le();
4683 __struct.target_system = buf.get_u8();
4684 __struct.target_component = buf.get_u8();
4685 let tmp = buf.get_u8();
4686 __struct.mission_type =
4687 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
4688 enum_type: "MavMissionType",
4689 value: tmp as u32,
4690 })?;
4691 __struct.opaque_id = buf.get_u32_le();
4692 Ok(__struct)
4693 }
4694 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4695 let mut __tmp = BytesMut::new(bytes);
4696 #[allow(clippy::absurd_extreme_comparisons)]
4697 #[allow(unused_comparisons)]
4698 if __tmp.remaining() < Self::ENCODED_LEN {
4699 panic!(
4700 "buffer is too small (need {} bytes, but got {})",
4701 Self::ENCODED_LEN,
4702 __tmp.remaining(),
4703 )
4704 }
4705 __tmp.put_u16_le(self.count);
4706 __tmp.put_u8(self.target_system);
4707 __tmp.put_u8(self.target_component);
4708 __tmp.put_u8(self.mission_type as u8);
4709 __tmp.put_u32_le(self.opaque_id);
4710 if matches!(version, MavlinkVersion::V2) {
4711 let len = __tmp.len();
4712 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4713 } else {
4714 __tmp.len()
4715 }
4716 }
4717}
4718#[doc = "id: 2"]
4719#[doc = "The system time is the time of the master clock. This can be emitted by flight controllers, onboard computers, or other components in the MAVLink network. Components that are using a less reliable time source, such as a battery-backed real time clock, can choose to match their system clock to that of a SYSTEM_TYPE that indicates a more recent time. This allows more broadly accurate date stamping of logs, and so on. If precise time synchronization is needed then use TIMESYNC instead."]
4720#[derive(Debug, Clone, PartialEq)]
4721#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4722#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4723pub struct SYSTEM_TIME_DATA {
4724 #[doc = "Timestamp (UNIX epoch time)."]
4725 pub time_unix_usec: u64,
4726 #[doc = "Timestamp (time since system boot)."]
4727 pub time_boot_ms: u32,
4728}
4729impl SYSTEM_TIME_DATA {
4730 pub const ENCODED_LEN: usize = 12usize;
4731 pub const DEFAULT: Self = Self {
4732 time_unix_usec: 0_u64,
4733 time_boot_ms: 0_u32,
4734 };
4735 #[cfg(feature = "arbitrary")]
4736 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4737 use arbitrary::{Arbitrary, Unstructured};
4738 let mut buf = [0u8; 1024];
4739 rng.fill_bytes(&mut buf);
4740 let mut unstructured = Unstructured::new(&buf);
4741 Self::arbitrary(&mut unstructured).unwrap_or_default()
4742 }
4743}
4744impl Default for SYSTEM_TIME_DATA {
4745 fn default() -> Self {
4746 Self::DEFAULT.clone()
4747 }
4748}
4749impl MessageData for SYSTEM_TIME_DATA {
4750 type Message = MavMessage;
4751 const ID: u32 = 2u32;
4752 const NAME: &'static str = "SYSTEM_TIME";
4753 const EXTRA_CRC: u8 = 137u8;
4754 const ENCODED_LEN: usize = 12usize;
4755 fn deser(
4756 _version: MavlinkVersion,
4757 __input: &[u8],
4758 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4759 let avail_len = __input.len();
4760 let mut payload_buf = [0; Self::ENCODED_LEN];
4761 let mut buf = if avail_len < Self::ENCODED_LEN {
4762 payload_buf[0..avail_len].copy_from_slice(__input);
4763 Bytes::new(&payload_buf)
4764 } else {
4765 Bytes::new(__input)
4766 };
4767 let mut __struct = Self::default();
4768 __struct.time_unix_usec = buf.get_u64_le();
4769 __struct.time_boot_ms = buf.get_u32_le();
4770 Ok(__struct)
4771 }
4772 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4773 let mut __tmp = BytesMut::new(bytes);
4774 #[allow(clippy::absurd_extreme_comparisons)]
4775 #[allow(unused_comparisons)]
4776 if __tmp.remaining() < Self::ENCODED_LEN {
4777 panic!(
4778 "buffer is too small (need {} bytes, but got {})",
4779 Self::ENCODED_LEN,
4780 __tmp.remaining(),
4781 )
4782 }
4783 __tmp.put_u64_le(self.time_unix_usec);
4784 __tmp.put_u32_le(self.time_boot_ms);
4785 if matches!(version, MavlinkVersion::V2) {
4786 let len = __tmp.len();
4787 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4788 } else {
4789 __tmp.len()
4790 }
4791 }
4792}
4793#[doc = "id: 1"]
4794#[doc = "The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows whether the system is currently active or not and if an emergency occurred. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occurred it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout."]
4795#[derive(Debug, Clone, PartialEq)]
4796#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4797#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4798pub struct SYS_STATUS_DATA {
4799 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
4800 pub onboard_control_sensors_present: MavSysStatusSensor,
4801 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
4802 pub onboard_control_sensors_enabled: MavSysStatusSensor,
4803 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
4804 pub onboard_control_sensors_health: MavSysStatusSensor,
4805 #[doc = "Maximum usage in percent of the mainloop time. Values: [0-1000] - should always be below 1000"]
4806 pub load: u16,
4807 #[doc = "Battery voltage, UINT16_MAX: Voltage not sent by autopilot"]
4808 pub voltage_battery: u16,
4809 #[doc = "Battery current, -1: Current not sent by autopilot"]
4810 pub current_battery: i16,
4811 #[doc = "Communication drop rate, (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
4812 pub drop_rate_comm: u16,
4813 #[doc = "Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)"]
4814 pub errors_comm: u16,
4815 #[doc = "Autopilot-specific errors"]
4816 pub errors_count1: u16,
4817 #[doc = "Autopilot-specific errors"]
4818 pub errors_count2: u16,
4819 #[doc = "Autopilot-specific errors"]
4820 pub errors_count3: u16,
4821 #[doc = "Autopilot-specific errors"]
4822 pub errors_count4: u16,
4823 #[doc = "Battery energy remaining, -1: Battery remaining energy not sent by autopilot"]
4824 pub battery_remaining: i8,
4825 #[doc = "Bitmap showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present."]
4826 #[cfg_attr(feature = "serde", serde(default))]
4827 pub onboard_control_sensors_present_extended: MavSysStatusSensorExtended,
4828 #[doc = "Bitmap showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled."]
4829 #[cfg_attr(feature = "serde", serde(default))]
4830 pub onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended,
4831 #[doc = "Bitmap showing which onboard controllers and sensors have an error (or are operational). Value of 0: error. Value of 1: healthy."]
4832 #[cfg_attr(feature = "serde", serde(default))]
4833 pub onboard_control_sensors_health_extended: MavSysStatusSensorExtended,
4834}
4835impl SYS_STATUS_DATA {
4836 pub const ENCODED_LEN: usize = 43usize;
4837 pub const DEFAULT: Self = Self {
4838 onboard_control_sensors_present: MavSysStatusSensor::DEFAULT,
4839 onboard_control_sensors_enabled: MavSysStatusSensor::DEFAULT,
4840 onboard_control_sensors_health: MavSysStatusSensor::DEFAULT,
4841 load: 0_u16,
4842 voltage_battery: 0_u16,
4843 current_battery: 0_i16,
4844 drop_rate_comm: 0_u16,
4845 errors_comm: 0_u16,
4846 errors_count1: 0_u16,
4847 errors_count2: 0_u16,
4848 errors_count3: 0_u16,
4849 errors_count4: 0_u16,
4850 battery_remaining: 0_i8,
4851 onboard_control_sensors_present_extended: MavSysStatusSensorExtended::DEFAULT,
4852 onboard_control_sensors_enabled_extended: MavSysStatusSensorExtended::DEFAULT,
4853 onboard_control_sensors_health_extended: MavSysStatusSensorExtended::DEFAULT,
4854 };
4855 #[cfg(feature = "arbitrary")]
4856 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
4857 use arbitrary::{Arbitrary, Unstructured};
4858 let mut buf = [0u8; 1024];
4859 rng.fill_bytes(&mut buf);
4860 let mut unstructured = Unstructured::new(&buf);
4861 Self::arbitrary(&mut unstructured).unwrap_or_default()
4862 }
4863}
4864impl Default for SYS_STATUS_DATA {
4865 fn default() -> Self {
4866 Self::DEFAULT.clone()
4867 }
4868}
4869impl MessageData for SYS_STATUS_DATA {
4870 type Message = MavMessage;
4871 const ID: u32 = 1u32;
4872 const NAME: &'static str = "SYS_STATUS";
4873 const EXTRA_CRC: u8 = 124u8;
4874 const ENCODED_LEN: usize = 43usize;
4875 fn deser(
4876 _version: MavlinkVersion,
4877 __input: &[u8],
4878 ) -> Result<Self, ::mavlink_core::error::ParserError> {
4879 let avail_len = __input.len();
4880 let mut payload_buf = [0; Self::ENCODED_LEN];
4881 let mut buf = if avail_len < Self::ENCODED_LEN {
4882 payload_buf[0..avail_len].copy_from_slice(__input);
4883 Bytes::new(&payload_buf)
4884 } else {
4885 Bytes::new(__input)
4886 };
4887 let mut __struct = Self::default();
4888 let tmp = buf.get_u32_le();
4889 __struct.onboard_control_sensors_present = MavSysStatusSensor::from_bits(
4890 tmp & MavSysStatusSensor::all().bits(),
4891 )
4892 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
4893 flag_type: "MavSysStatusSensor",
4894 value: tmp as u32,
4895 })?;
4896 let tmp = buf.get_u32_le();
4897 __struct.onboard_control_sensors_enabled = MavSysStatusSensor::from_bits(
4898 tmp & MavSysStatusSensor::all().bits(),
4899 )
4900 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
4901 flag_type: "MavSysStatusSensor",
4902 value: tmp as u32,
4903 })?;
4904 let tmp = buf.get_u32_le();
4905 __struct.onboard_control_sensors_health = MavSysStatusSensor::from_bits(
4906 tmp & MavSysStatusSensor::all().bits(),
4907 )
4908 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
4909 flag_type: "MavSysStatusSensor",
4910 value: tmp as u32,
4911 })?;
4912 __struct.load = buf.get_u16_le();
4913 __struct.voltage_battery = buf.get_u16_le();
4914 __struct.current_battery = buf.get_i16_le();
4915 __struct.drop_rate_comm = buf.get_u16_le();
4916 __struct.errors_comm = buf.get_u16_le();
4917 __struct.errors_count1 = buf.get_u16_le();
4918 __struct.errors_count2 = buf.get_u16_le();
4919 __struct.errors_count3 = buf.get_u16_le();
4920 __struct.errors_count4 = buf.get_u16_le();
4921 __struct.battery_remaining = buf.get_i8();
4922 let tmp = buf.get_u32_le();
4923 __struct.onboard_control_sensors_present_extended =
4924 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
4925 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
4926 flag_type: "MavSysStatusSensorExtended",
4927 value: tmp as u32,
4928 })?;
4929 let tmp = buf.get_u32_le();
4930 __struct.onboard_control_sensors_enabled_extended =
4931 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
4932 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
4933 flag_type: "MavSysStatusSensorExtended",
4934 value: tmp as u32,
4935 })?;
4936 let tmp = buf.get_u32_le();
4937 __struct.onboard_control_sensors_health_extended =
4938 MavSysStatusSensorExtended::from_bits(tmp & MavSysStatusSensorExtended::all().bits())
4939 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
4940 flag_type: "MavSysStatusSensorExtended",
4941 value: tmp as u32,
4942 })?;
4943 Ok(__struct)
4944 }
4945 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
4946 let mut __tmp = BytesMut::new(bytes);
4947 #[allow(clippy::absurd_extreme_comparisons)]
4948 #[allow(unused_comparisons)]
4949 if __tmp.remaining() < Self::ENCODED_LEN {
4950 panic!(
4951 "buffer is too small (need {} bytes, but got {})",
4952 Self::ENCODED_LEN,
4953 __tmp.remaining(),
4954 )
4955 }
4956 __tmp.put_u32_le(self.onboard_control_sensors_present.bits());
4957 __tmp.put_u32_le(self.onboard_control_sensors_enabled.bits());
4958 __tmp.put_u32_le(self.onboard_control_sensors_health.bits());
4959 __tmp.put_u16_le(self.load);
4960 __tmp.put_u16_le(self.voltage_battery);
4961 __tmp.put_i16_le(self.current_battery);
4962 __tmp.put_u16_le(self.drop_rate_comm);
4963 __tmp.put_u16_le(self.errors_comm);
4964 __tmp.put_u16_le(self.errors_count1);
4965 __tmp.put_u16_le(self.errors_count2);
4966 __tmp.put_u16_le(self.errors_count3);
4967 __tmp.put_u16_le(self.errors_count4);
4968 __tmp.put_i8(self.battery_remaining);
4969 __tmp.put_u32_le(self.onboard_control_sensors_present_extended.bits());
4970 __tmp.put_u32_le(self.onboard_control_sensors_enabled_extended.bits());
4971 __tmp.put_u32_le(self.onboard_control_sensors_health_extended.bits());
4972 if matches!(version, MavlinkVersion::V2) {
4973 let len = __tmp.len();
4974 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
4975 } else {
4976 __tmp.len()
4977 }
4978 }
4979}
4980#[doc = "id: 246"]
4981#[doc = "The location and information of an ADSB vehicle."]
4982#[derive(Debug, Clone, PartialEq)]
4983#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
4984#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
4985pub struct ADSB_VEHICLE_DATA {
4986 #[doc = "ICAO address"]
4987 pub ICAO_address: u32,
4988 #[doc = "Latitude"]
4989 pub lat: i32,
4990 #[doc = "Longitude"]
4991 pub lon: i32,
4992 #[doc = "Altitude(ASL)"]
4993 pub altitude: i32,
4994 #[doc = "Course over ground"]
4995 pub heading: u16,
4996 #[doc = "The horizontal velocity"]
4997 pub hor_velocity: u16,
4998 #[doc = "The vertical velocity. Positive is up"]
4999 pub ver_velocity: i16,
5000 #[doc = "Bitmap to indicate various statuses including valid data fields"]
5001 pub flags: AdsbFlags,
5002 #[doc = "Squawk code. Note that the code is in decimal: e.g. 7700 (general emergency) is encoded as binary 0b0001_1110_0001_0100, not(!) as 0b0000_111_111_000_000"]
5003 pub squawk: u16,
5004 #[doc = "ADSB altitude type."]
5005 pub altitude_type: AdsbAltitudeType,
5006 #[doc = "The callsign, 8+null"]
5007 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5008 pub callsign: [u8; 9],
5009 #[doc = "ADSB emitter type."]
5010 pub emitter_type: AdsbEmitterType,
5011 #[doc = "Time since last communication in seconds"]
5012 pub tslc: u8,
5013}
5014impl ADSB_VEHICLE_DATA {
5015 pub const ENCODED_LEN: usize = 38usize;
5016 pub const DEFAULT: Self = Self {
5017 ICAO_address: 0_u32,
5018 lat: 0_i32,
5019 lon: 0_i32,
5020 altitude: 0_i32,
5021 heading: 0_u16,
5022 hor_velocity: 0_u16,
5023 ver_velocity: 0_i16,
5024 flags: AdsbFlags::DEFAULT,
5025 squawk: 0_u16,
5026 altitude_type: AdsbAltitudeType::DEFAULT,
5027 callsign: [0_u8; 9usize],
5028 emitter_type: AdsbEmitterType::DEFAULT,
5029 tslc: 0_u8,
5030 };
5031 #[cfg(feature = "arbitrary")]
5032 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5033 use arbitrary::{Arbitrary, Unstructured};
5034 let mut buf = [0u8; 1024];
5035 rng.fill_bytes(&mut buf);
5036 let mut unstructured = Unstructured::new(&buf);
5037 Self::arbitrary(&mut unstructured).unwrap_or_default()
5038 }
5039}
5040impl Default for ADSB_VEHICLE_DATA {
5041 fn default() -> Self {
5042 Self::DEFAULT.clone()
5043 }
5044}
5045impl MessageData for ADSB_VEHICLE_DATA {
5046 type Message = MavMessage;
5047 const ID: u32 = 246u32;
5048 const NAME: &'static str = "ADSB_VEHICLE";
5049 const EXTRA_CRC: u8 = 184u8;
5050 const ENCODED_LEN: usize = 38usize;
5051 fn deser(
5052 _version: MavlinkVersion,
5053 __input: &[u8],
5054 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5055 let avail_len = __input.len();
5056 let mut payload_buf = [0; Self::ENCODED_LEN];
5057 let mut buf = if avail_len < Self::ENCODED_LEN {
5058 payload_buf[0..avail_len].copy_from_slice(__input);
5059 Bytes::new(&payload_buf)
5060 } else {
5061 Bytes::new(__input)
5062 };
5063 let mut __struct = Self::default();
5064 __struct.ICAO_address = buf.get_u32_le();
5065 __struct.lat = buf.get_i32_le();
5066 __struct.lon = buf.get_i32_le();
5067 __struct.altitude = buf.get_i32_le();
5068 __struct.heading = buf.get_u16_le();
5069 __struct.hor_velocity = buf.get_u16_le();
5070 __struct.ver_velocity = buf.get_i16_le();
5071 let tmp = buf.get_u16_le();
5072 __struct.flags = AdsbFlags::from_bits(tmp & AdsbFlags::all().bits()).ok_or(
5073 ::mavlink_core::error::ParserError::InvalidFlag {
5074 flag_type: "AdsbFlags",
5075 value: tmp as u32,
5076 },
5077 )?;
5078 __struct.squawk = buf.get_u16_le();
5079 let tmp = buf.get_u8();
5080 __struct.altitude_type =
5081 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5082 enum_type: "AdsbAltitudeType",
5083 value: tmp as u32,
5084 })?;
5085 for v in &mut __struct.callsign {
5086 let val = buf.get_u8();
5087 *v = val;
5088 }
5089 let tmp = buf.get_u8();
5090 __struct.emitter_type =
5091 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5092 enum_type: "AdsbEmitterType",
5093 value: tmp as u32,
5094 })?;
5095 __struct.tslc = buf.get_u8();
5096 Ok(__struct)
5097 }
5098 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5099 let mut __tmp = BytesMut::new(bytes);
5100 #[allow(clippy::absurd_extreme_comparisons)]
5101 #[allow(unused_comparisons)]
5102 if __tmp.remaining() < Self::ENCODED_LEN {
5103 panic!(
5104 "buffer is too small (need {} bytes, but got {})",
5105 Self::ENCODED_LEN,
5106 __tmp.remaining(),
5107 )
5108 }
5109 __tmp.put_u32_le(self.ICAO_address);
5110 __tmp.put_i32_le(self.lat);
5111 __tmp.put_i32_le(self.lon);
5112 __tmp.put_i32_le(self.altitude);
5113 __tmp.put_u16_le(self.heading);
5114 __tmp.put_u16_le(self.hor_velocity);
5115 __tmp.put_i16_le(self.ver_velocity);
5116 __tmp.put_u16_le(self.flags.bits());
5117 __tmp.put_u16_le(self.squawk);
5118 __tmp.put_u8(self.altitude_type as u8);
5119 for val in &self.callsign {
5120 __tmp.put_u8(*val);
5121 }
5122 __tmp.put_u8(self.emitter_type as u8);
5123 __tmp.put_u8(self.tslc);
5124 if matches!(version, MavlinkVersion::V2) {
5125 let len = __tmp.len();
5126 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5127 } else {
5128 __tmp.len()
5129 }
5130 }
5131}
5132#[doc = "id: 385"]
5133#[doc = "Message for transporting \"arbitrary\" variable-length data from one component to another (broadcast is not forbidden, but discouraged). The encoding of the data is usually extension specific, i.e. determined by the source, and is usually not documented as part of the MAVLink specification."]
5134#[derive(Debug, Clone, PartialEq)]
5135#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5136#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5137pub struct TUNNEL_DATA {
5138 #[doc = "A code that identifies the content of the payload (0 for unknown, which is the default). If this code is less than 32768, it is a 'registered' payload type and the corresponding code should be added to the MAV_TUNNEL_PAYLOAD_TYPE enum. Software creators can register blocks of types as needed. Codes greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
5139 pub payload_type: MavTunnelPayloadType,
5140 #[doc = "System ID (can be 0 for broadcast, but this is discouraged)"]
5141 pub target_system: u8,
5142 #[doc = "Component ID (can be 0 for broadcast, but this is discouraged)"]
5143 pub target_component: u8,
5144 #[doc = "Length of the data transported in payload"]
5145 pub payload_length: u8,
5146 #[doc = "Variable length payload. The payload length is defined by payload_length. The entire content of this block is opaque unless you understand the encoding specified by payload_type."]
5147 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5148 pub payload: [u8; 128],
5149}
5150impl TUNNEL_DATA {
5151 pub const ENCODED_LEN: usize = 133usize;
5152 pub const DEFAULT: Self = Self {
5153 payload_type: MavTunnelPayloadType::DEFAULT,
5154 target_system: 0_u8,
5155 target_component: 0_u8,
5156 payload_length: 0_u8,
5157 payload: [0_u8; 128usize],
5158 };
5159 #[cfg(feature = "arbitrary")]
5160 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5161 use arbitrary::{Arbitrary, Unstructured};
5162 let mut buf = [0u8; 1024];
5163 rng.fill_bytes(&mut buf);
5164 let mut unstructured = Unstructured::new(&buf);
5165 Self::arbitrary(&mut unstructured).unwrap_or_default()
5166 }
5167}
5168impl Default for TUNNEL_DATA {
5169 fn default() -> Self {
5170 Self::DEFAULT.clone()
5171 }
5172}
5173impl MessageData for TUNNEL_DATA {
5174 type Message = MavMessage;
5175 const ID: u32 = 385u32;
5176 const NAME: &'static str = "TUNNEL";
5177 const EXTRA_CRC: u8 = 147u8;
5178 const ENCODED_LEN: usize = 133usize;
5179 fn deser(
5180 _version: MavlinkVersion,
5181 __input: &[u8],
5182 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5183 let avail_len = __input.len();
5184 let mut payload_buf = [0; Self::ENCODED_LEN];
5185 let mut buf = if avail_len < Self::ENCODED_LEN {
5186 payload_buf[0..avail_len].copy_from_slice(__input);
5187 Bytes::new(&payload_buf)
5188 } else {
5189 Bytes::new(__input)
5190 };
5191 let mut __struct = Self::default();
5192 let tmp = buf.get_u16_le();
5193 __struct.payload_type = FromPrimitive::from_u16(tmp).ok_or(
5194 ::mavlink_core::error::ParserError::InvalidEnum {
5195 enum_type: "MavTunnelPayloadType",
5196 value: tmp as u32,
5197 },
5198 )?;
5199 __struct.target_system = buf.get_u8();
5200 __struct.target_component = buf.get_u8();
5201 __struct.payload_length = buf.get_u8();
5202 for v in &mut __struct.payload {
5203 let val = buf.get_u8();
5204 *v = val;
5205 }
5206 Ok(__struct)
5207 }
5208 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5209 let mut __tmp = BytesMut::new(bytes);
5210 #[allow(clippy::absurd_extreme_comparisons)]
5211 #[allow(unused_comparisons)]
5212 if __tmp.remaining() < Self::ENCODED_LEN {
5213 panic!(
5214 "buffer is too small (need {} bytes, but got {})",
5215 Self::ENCODED_LEN,
5216 __tmp.remaining(),
5217 )
5218 }
5219 __tmp.put_u16_le(self.payload_type as u16);
5220 __tmp.put_u8(self.target_system);
5221 __tmp.put_u8(self.target_component);
5222 __tmp.put_u8(self.payload_length);
5223 for val in &self.payload {
5224 __tmp.put_u8(*val);
5225 }
5226 if matches!(version, MavlinkVersion::V2) {
5227 let len = __tmp.len();
5228 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5229 } else {
5230 __tmp.len()
5231 }
5232 }
5233}
5234#[doc = "id: 12918"]
5235#[doc = "Transmitter (remote ID system) is enabled and ready to start sending location and other required information. This is streamed by transmitter. A flight controller uses it as a condition to arm."]
5236#[derive(Debug, Clone, PartialEq)]
5237#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5238#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5239pub struct OPEN_DRONE_ID_ARM_STATUS_DATA {
5240 #[doc = "Status level indicating if arming is allowed."]
5241 pub status: MavOdidArmStatus,
5242 #[doc = "Text error message, should be empty if status is good to arm. Fill with nulls in unused portion."]
5243 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5244 pub error: [u8; 50],
5245}
5246impl OPEN_DRONE_ID_ARM_STATUS_DATA {
5247 pub const ENCODED_LEN: usize = 51usize;
5248 pub const DEFAULT: Self = Self {
5249 status: MavOdidArmStatus::DEFAULT,
5250 error: [0_u8; 50usize],
5251 };
5252 #[cfg(feature = "arbitrary")]
5253 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5254 use arbitrary::{Arbitrary, Unstructured};
5255 let mut buf = [0u8; 1024];
5256 rng.fill_bytes(&mut buf);
5257 let mut unstructured = Unstructured::new(&buf);
5258 Self::arbitrary(&mut unstructured).unwrap_or_default()
5259 }
5260}
5261impl Default for OPEN_DRONE_ID_ARM_STATUS_DATA {
5262 fn default() -> Self {
5263 Self::DEFAULT.clone()
5264 }
5265}
5266impl MessageData for OPEN_DRONE_ID_ARM_STATUS_DATA {
5267 type Message = MavMessage;
5268 const ID: u32 = 12918u32;
5269 const NAME: &'static str = "OPEN_DRONE_ID_ARM_STATUS";
5270 const EXTRA_CRC: u8 = 139u8;
5271 const ENCODED_LEN: usize = 51usize;
5272 fn deser(
5273 _version: MavlinkVersion,
5274 __input: &[u8],
5275 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5276 let avail_len = __input.len();
5277 let mut payload_buf = [0; Self::ENCODED_LEN];
5278 let mut buf = if avail_len < Self::ENCODED_LEN {
5279 payload_buf[0..avail_len].copy_from_slice(__input);
5280 Bytes::new(&payload_buf)
5281 } else {
5282 Bytes::new(__input)
5283 };
5284 let mut __struct = Self::default();
5285 let tmp = buf.get_u8();
5286 __struct.status =
5287 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5288 enum_type: "MavOdidArmStatus",
5289 value: tmp as u32,
5290 })?;
5291 for v in &mut __struct.error {
5292 let val = buf.get_u8();
5293 *v = val;
5294 }
5295 Ok(__struct)
5296 }
5297 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5298 let mut __tmp = BytesMut::new(bytes);
5299 #[allow(clippy::absurd_extreme_comparisons)]
5300 #[allow(unused_comparisons)]
5301 if __tmp.remaining() < Self::ENCODED_LEN {
5302 panic!(
5303 "buffer is too small (need {} bytes, but got {})",
5304 Self::ENCODED_LEN,
5305 __tmp.remaining(),
5306 )
5307 }
5308 __tmp.put_u8(self.status as u8);
5309 for val in &self.error {
5310 __tmp.put_u8(*val);
5311 }
5312 if matches!(version, MavlinkVersion::V2) {
5313 let len = __tmp.len();
5314 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5315 } else {
5316 __tmp.len()
5317 }
5318 }
5319}
5320#[doc = "id: 27"]
5321#[doc = "The RAW IMU readings for a 9DOF sensor, which is identified by the id (default IMU1). This message should always contain the true raw values without any scaling to allow data capture and system debugging."]
5322#[derive(Debug, Clone, PartialEq)]
5323#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5324#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5325pub struct RAW_IMU_DATA {
5326 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5327 pub time_usec: u64,
5328 #[doc = "X acceleration (raw)"]
5329 pub xacc: i16,
5330 #[doc = "Y acceleration (raw)"]
5331 pub yacc: i16,
5332 #[doc = "Z acceleration (raw)"]
5333 pub zacc: i16,
5334 #[doc = "Angular speed around X axis (raw)"]
5335 pub xgyro: i16,
5336 #[doc = "Angular speed around Y axis (raw)"]
5337 pub ygyro: i16,
5338 #[doc = "Angular speed around Z axis (raw)"]
5339 pub zgyro: i16,
5340 #[doc = "X Magnetic field (raw)"]
5341 pub xmag: i16,
5342 #[doc = "Y Magnetic field (raw)"]
5343 pub ymag: i16,
5344 #[doc = "Z Magnetic field (raw)"]
5345 pub zmag: i16,
5346 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
5347 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5348 pub id: u8,
5349 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
5350 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5351 pub temperature: i16,
5352}
5353impl RAW_IMU_DATA {
5354 pub const ENCODED_LEN: usize = 29usize;
5355 pub const DEFAULT: Self = Self {
5356 time_usec: 0_u64,
5357 xacc: 0_i16,
5358 yacc: 0_i16,
5359 zacc: 0_i16,
5360 xgyro: 0_i16,
5361 ygyro: 0_i16,
5362 zgyro: 0_i16,
5363 xmag: 0_i16,
5364 ymag: 0_i16,
5365 zmag: 0_i16,
5366 id: 0_u8,
5367 temperature: 0_i16,
5368 };
5369 #[cfg(feature = "arbitrary")]
5370 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5371 use arbitrary::{Arbitrary, Unstructured};
5372 let mut buf = [0u8; 1024];
5373 rng.fill_bytes(&mut buf);
5374 let mut unstructured = Unstructured::new(&buf);
5375 Self::arbitrary(&mut unstructured).unwrap_or_default()
5376 }
5377}
5378impl Default for RAW_IMU_DATA {
5379 fn default() -> Self {
5380 Self::DEFAULT.clone()
5381 }
5382}
5383impl MessageData for RAW_IMU_DATA {
5384 type Message = MavMessage;
5385 const ID: u32 = 27u32;
5386 const NAME: &'static str = "RAW_IMU";
5387 const EXTRA_CRC: u8 = 144u8;
5388 const ENCODED_LEN: usize = 29usize;
5389 fn deser(
5390 _version: MavlinkVersion,
5391 __input: &[u8],
5392 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5393 let avail_len = __input.len();
5394 let mut payload_buf = [0; Self::ENCODED_LEN];
5395 let mut buf = if avail_len < Self::ENCODED_LEN {
5396 payload_buf[0..avail_len].copy_from_slice(__input);
5397 Bytes::new(&payload_buf)
5398 } else {
5399 Bytes::new(__input)
5400 };
5401 let mut __struct = Self::default();
5402 __struct.time_usec = buf.get_u64_le();
5403 __struct.xacc = buf.get_i16_le();
5404 __struct.yacc = buf.get_i16_le();
5405 __struct.zacc = buf.get_i16_le();
5406 __struct.xgyro = buf.get_i16_le();
5407 __struct.ygyro = buf.get_i16_le();
5408 __struct.zgyro = buf.get_i16_le();
5409 __struct.xmag = buf.get_i16_le();
5410 __struct.ymag = buf.get_i16_le();
5411 __struct.zmag = buf.get_i16_le();
5412 __struct.id = buf.get_u8();
5413 __struct.temperature = buf.get_i16_le();
5414 Ok(__struct)
5415 }
5416 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5417 let mut __tmp = BytesMut::new(bytes);
5418 #[allow(clippy::absurd_extreme_comparisons)]
5419 #[allow(unused_comparisons)]
5420 if __tmp.remaining() < Self::ENCODED_LEN {
5421 panic!(
5422 "buffer is too small (need {} bytes, but got {})",
5423 Self::ENCODED_LEN,
5424 __tmp.remaining(),
5425 )
5426 }
5427 __tmp.put_u64_le(self.time_usec);
5428 __tmp.put_i16_le(self.xacc);
5429 __tmp.put_i16_le(self.yacc);
5430 __tmp.put_i16_le(self.zacc);
5431 __tmp.put_i16_le(self.xgyro);
5432 __tmp.put_i16_le(self.ygyro);
5433 __tmp.put_i16_le(self.zgyro);
5434 __tmp.put_i16_le(self.xmag);
5435 __tmp.put_i16_le(self.ymag);
5436 __tmp.put_i16_le(self.zmag);
5437 __tmp.put_u8(self.id);
5438 __tmp.put_i16_le(self.temperature);
5439 if matches!(version, MavlinkVersion::V2) {
5440 let len = __tmp.len();
5441 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5442 } else {
5443 __tmp.len()
5444 }
5445 }
5446}
5447#[doc = "id: 42"]
5448#[doc = "Message that announces the sequence number of the current target mission item (that the system will fly towards/execute when the mission is running). This message should be streamed all the time (nominally at 1Hz). This message should be emitted following a call to MAV_CMD_DO_SET_MISSION_CURRENT or MISSION_SET_CURRENT."]
5449#[derive(Debug, Clone, PartialEq)]
5450#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5451#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5452pub struct MISSION_CURRENT_DATA {
5453 #[doc = "Sequence"]
5454 pub seq: u16,
5455 #[doc = "Total number of mission items on vehicle (on last item, sequence == total). If the autopilot stores its home location as part of the mission this will be excluded from the total. 0: Not supported, UINT16_MAX if no mission is present on the vehicle."]
5456 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5457 pub total: u16,
5458 #[doc = "Mission state machine state. MISSION_STATE_UNKNOWN if state reporting not supported."]
5459 #[cfg_attr(feature = "serde", serde(default))]
5460 pub mission_state: MissionState,
5461 #[doc = "Vehicle is in a mode that can execute mission items or suspended. 0: Unknown, 1: In mission mode, 2: Suspended (not in mission mode)."]
5462 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5463 pub mission_mode: u8,
5464 #[doc = "Id of current on-vehicle mission plan, or 0 if IDs are not supported or there is no mission loaded. GCS can use this to track changes to the mission plan type. The same value is returned on mission upload (in the MISSION_ACK)."]
5465 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5466 pub mission_id: u32,
5467 #[doc = "Id of current on-vehicle fence plan, or 0 if IDs are not supported or there is no fence loaded. GCS can use this to track changes to the fence plan type. The same value is returned on fence upload (in the MISSION_ACK)."]
5468 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5469 pub fence_id: u32,
5470 #[doc = "Id of current on-vehicle rally point plan, or 0 if IDs are not supported or there are no rally points loaded. GCS can use this to track changes to the rally point plan type. The same value is returned on rally point upload (in the MISSION_ACK)."]
5471 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5472 pub rally_points_id: u32,
5473}
5474impl MISSION_CURRENT_DATA {
5475 pub const ENCODED_LEN: usize = 18usize;
5476 pub const DEFAULT: Self = Self {
5477 seq: 0_u16,
5478 total: 0_u16,
5479 mission_state: MissionState::DEFAULT,
5480 mission_mode: 0_u8,
5481 mission_id: 0_u32,
5482 fence_id: 0_u32,
5483 rally_points_id: 0_u32,
5484 };
5485 #[cfg(feature = "arbitrary")]
5486 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5487 use arbitrary::{Arbitrary, Unstructured};
5488 let mut buf = [0u8; 1024];
5489 rng.fill_bytes(&mut buf);
5490 let mut unstructured = Unstructured::new(&buf);
5491 Self::arbitrary(&mut unstructured).unwrap_or_default()
5492 }
5493}
5494impl Default for MISSION_CURRENT_DATA {
5495 fn default() -> Self {
5496 Self::DEFAULT.clone()
5497 }
5498}
5499impl MessageData for MISSION_CURRENT_DATA {
5500 type Message = MavMessage;
5501 const ID: u32 = 42u32;
5502 const NAME: &'static str = "MISSION_CURRENT";
5503 const EXTRA_CRC: u8 = 28u8;
5504 const ENCODED_LEN: usize = 18usize;
5505 fn deser(
5506 _version: MavlinkVersion,
5507 __input: &[u8],
5508 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5509 let avail_len = __input.len();
5510 let mut payload_buf = [0; Self::ENCODED_LEN];
5511 let mut buf = if avail_len < Self::ENCODED_LEN {
5512 payload_buf[0..avail_len].copy_from_slice(__input);
5513 Bytes::new(&payload_buf)
5514 } else {
5515 Bytes::new(__input)
5516 };
5517 let mut __struct = Self::default();
5518 __struct.seq = buf.get_u16_le();
5519 __struct.total = buf.get_u16_le();
5520 let tmp = buf.get_u8();
5521 __struct.mission_state =
5522 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5523 enum_type: "MissionState",
5524 value: tmp as u32,
5525 })?;
5526 __struct.mission_mode = buf.get_u8();
5527 __struct.mission_id = buf.get_u32_le();
5528 __struct.fence_id = buf.get_u32_le();
5529 __struct.rally_points_id = buf.get_u32_le();
5530 Ok(__struct)
5531 }
5532 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5533 let mut __tmp = BytesMut::new(bytes);
5534 #[allow(clippy::absurd_extreme_comparisons)]
5535 #[allow(unused_comparisons)]
5536 if __tmp.remaining() < Self::ENCODED_LEN {
5537 panic!(
5538 "buffer is too small (need {} bytes, but got {})",
5539 Self::ENCODED_LEN,
5540 __tmp.remaining(),
5541 )
5542 }
5543 __tmp.put_u16_le(self.seq);
5544 __tmp.put_u16_le(self.total);
5545 __tmp.put_u8(self.mission_state as u8);
5546 __tmp.put_u8(self.mission_mode);
5547 __tmp.put_u32_le(self.mission_id);
5548 __tmp.put_u32_le(self.fence_id);
5549 __tmp.put_u32_le(self.rally_points_id);
5550 if matches!(version, MavlinkVersion::V2) {
5551 let len = __tmp.len();
5552 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5553 } else {
5554 __tmp.len()
5555 }
5556 }
5557}
5558#[doc = "id: 90"]
5559#[doc = "Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations."]
5560#[derive(Debug, Clone, PartialEq)]
5561#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5562#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5563pub struct HIL_STATE_DATA {
5564 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5565 pub time_usec: u64,
5566 #[doc = "Roll angle"]
5567 pub roll: f32,
5568 #[doc = "Pitch angle"]
5569 pub pitch: f32,
5570 #[doc = "Yaw angle"]
5571 pub yaw: f32,
5572 #[doc = "Body frame roll / phi angular speed"]
5573 pub rollspeed: f32,
5574 #[doc = "Body frame pitch / theta angular speed"]
5575 pub pitchspeed: f32,
5576 #[doc = "Body frame yaw / psi angular speed"]
5577 pub yawspeed: f32,
5578 #[doc = "Latitude"]
5579 pub lat: i32,
5580 #[doc = "Longitude"]
5581 pub lon: i32,
5582 #[doc = "Altitude"]
5583 pub alt: i32,
5584 #[doc = "Ground X Speed (Latitude)"]
5585 pub vx: i16,
5586 #[doc = "Ground Y Speed (Longitude)"]
5587 pub vy: i16,
5588 #[doc = "Ground Z Speed (Altitude)"]
5589 pub vz: i16,
5590 #[doc = "X acceleration"]
5591 pub xacc: i16,
5592 #[doc = "Y acceleration"]
5593 pub yacc: i16,
5594 #[doc = "Z acceleration"]
5595 pub zacc: i16,
5596}
5597impl HIL_STATE_DATA {
5598 pub const ENCODED_LEN: usize = 56usize;
5599 pub const DEFAULT: Self = Self {
5600 time_usec: 0_u64,
5601 roll: 0.0_f32,
5602 pitch: 0.0_f32,
5603 yaw: 0.0_f32,
5604 rollspeed: 0.0_f32,
5605 pitchspeed: 0.0_f32,
5606 yawspeed: 0.0_f32,
5607 lat: 0_i32,
5608 lon: 0_i32,
5609 alt: 0_i32,
5610 vx: 0_i16,
5611 vy: 0_i16,
5612 vz: 0_i16,
5613 xacc: 0_i16,
5614 yacc: 0_i16,
5615 zacc: 0_i16,
5616 };
5617 #[cfg(feature = "arbitrary")]
5618 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5619 use arbitrary::{Arbitrary, Unstructured};
5620 let mut buf = [0u8; 1024];
5621 rng.fill_bytes(&mut buf);
5622 let mut unstructured = Unstructured::new(&buf);
5623 Self::arbitrary(&mut unstructured).unwrap_or_default()
5624 }
5625}
5626impl Default for HIL_STATE_DATA {
5627 fn default() -> Self {
5628 Self::DEFAULT.clone()
5629 }
5630}
5631impl MessageData for HIL_STATE_DATA {
5632 type Message = MavMessage;
5633 const ID: u32 = 90u32;
5634 const NAME: &'static str = "HIL_STATE";
5635 const EXTRA_CRC: u8 = 183u8;
5636 const ENCODED_LEN: usize = 56usize;
5637 fn deser(
5638 _version: MavlinkVersion,
5639 __input: &[u8],
5640 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5641 let avail_len = __input.len();
5642 let mut payload_buf = [0; Self::ENCODED_LEN];
5643 let mut buf = if avail_len < Self::ENCODED_LEN {
5644 payload_buf[0..avail_len].copy_from_slice(__input);
5645 Bytes::new(&payload_buf)
5646 } else {
5647 Bytes::new(__input)
5648 };
5649 let mut __struct = Self::default();
5650 __struct.time_usec = buf.get_u64_le();
5651 __struct.roll = buf.get_f32_le();
5652 __struct.pitch = buf.get_f32_le();
5653 __struct.yaw = buf.get_f32_le();
5654 __struct.rollspeed = buf.get_f32_le();
5655 __struct.pitchspeed = buf.get_f32_le();
5656 __struct.yawspeed = buf.get_f32_le();
5657 __struct.lat = buf.get_i32_le();
5658 __struct.lon = buf.get_i32_le();
5659 __struct.alt = buf.get_i32_le();
5660 __struct.vx = buf.get_i16_le();
5661 __struct.vy = buf.get_i16_le();
5662 __struct.vz = buf.get_i16_le();
5663 __struct.xacc = buf.get_i16_le();
5664 __struct.yacc = buf.get_i16_le();
5665 __struct.zacc = buf.get_i16_le();
5666 Ok(__struct)
5667 }
5668 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5669 let mut __tmp = BytesMut::new(bytes);
5670 #[allow(clippy::absurd_extreme_comparisons)]
5671 #[allow(unused_comparisons)]
5672 if __tmp.remaining() < Self::ENCODED_LEN {
5673 panic!(
5674 "buffer is too small (need {} bytes, but got {})",
5675 Self::ENCODED_LEN,
5676 __tmp.remaining(),
5677 )
5678 }
5679 __tmp.put_u64_le(self.time_usec);
5680 __tmp.put_f32_le(self.roll);
5681 __tmp.put_f32_le(self.pitch);
5682 __tmp.put_f32_le(self.yaw);
5683 __tmp.put_f32_le(self.rollspeed);
5684 __tmp.put_f32_le(self.pitchspeed);
5685 __tmp.put_f32_le(self.yawspeed);
5686 __tmp.put_i32_le(self.lat);
5687 __tmp.put_i32_le(self.lon);
5688 __tmp.put_i32_le(self.alt);
5689 __tmp.put_i16_le(self.vx);
5690 __tmp.put_i16_le(self.vy);
5691 __tmp.put_i16_le(self.vz);
5692 __tmp.put_i16_le(self.xacc);
5693 __tmp.put_i16_le(self.yacc);
5694 __tmp.put_i16_le(self.zacc);
5695 if matches!(version, MavlinkVersion::V2) {
5696 let len = __tmp.len();
5697 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5698 } else {
5699 __tmp.len()
5700 }
5701 }
5702}
5703#[doc = "id: 330"]
5704#[doc = "Obstacle distances in front of the sensor, starting from the left in increment degrees to the right."]
5705#[derive(Debug, Clone, PartialEq)]
5706#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5707#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5708pub struct OBSTACLE_DISTANCE_DATA {
5709 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5710 pub time_usec: u64,
5711 #[doc = "Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm."]
5712 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5713 pub distances: [u16; 72],
5714 #[doc = "Minimum distance the sensor can measure."]
5715 pub min_distance: u16,
5716 #[doc = "Maximum distance the sensor can measure."]
5717 pub max_distance: u16,
5718 #[doc = "Class id of the distance sensor type."]
5719 pub sensor_type: MavDistanceSensor,
5720 #[doc = "Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero."]
5721 pub increment: u8,
5722 #[doc = "Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise."]
5723 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5724 pub increment_f: f32,
5725 #[doc = "Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise."]
5726 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
5727 pub angle_offset: f32,
5728 #[doc = "Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned."]
5729 #[cfg_attr(feature = "serde", serde(default))]
5730 pub frame: MavFrame,
5731}
5732impl OBSTACLE_DISTANCE_DATA {
5733 pub const ENCODED_LEN: usize = 167usize;
5734 pub const DEFAULT: Self = Self {
5735 time_usec: 0_u64,
5736 distances: [0_u16; 72usize],
5737 min_distance: 0_u16,
5738 max_distance: 0_u16,
5739 sensor_type: MavDistanceSensor::DEFAULT,
5740 increment: 0_u8,
5741 increment_f: 0.0_f32,
5742 angle_offset: 0.0_f32,
5743 frame: MavFrame::DEFAULT,
5744 };
5745 #[cfg(feature = "arbitrary")]
5746 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5747 use arbitrary::{Arbitrary, Unstructured};
5748 let mut buf = [0u8; 1024];
5749 rng.fill_bytes(&mut buf);
5750 let mut unstructured = Unstructured::new(&buf);
5751 Self::arbitrary(&mut unstructured).unwrap_or_default()
5752 }
5753}
5754impl Default for OBSTACLE_DISTANCE_DATA {
5755 fn default() -> Self {
5756 Self::DEFAULT.clone()
5757 }
5758}
5759impl MessageData for OBSTACLE_DISTANCE_DATA {
5760 type Message = MavMessage;
5761 const ID: u32 = 330u32;
5762 const NAME: &'static str = "OBSTACLE_DISTANCE";
5763 const EXTRA_CRC: u8 = 23u8;
5764 const ENCODED_LEN: usize = 167usize;
5765 fn deser(
5766 _version: MavlinkVersion,
5767 __input: &[u8],
5768 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5769 let avail_len = __input.len();
5770 let mut payload_buf = [0; Self::ENCODED_LEN];
5771 let mut buf = if avail_len < Self::ENCODED_LEN {
5772 payload_buf[0..avail_len].copy_from_slice(__input);
5773 Bytes::new(&payload_buf)
5774 } else {
5775 Bytes::new(__input)
5776 };
5777 let mut __struct = Self::default();
5778 __struct.time_usec = buf.get_u64_le();
5779 for v in &mut __struct.distances {
5780 let val = buf.get_u16_le();
5781 *v = val;
5782 }
5783 __struct.min_distance = buf.get_u16_le();
5784 __struct.max_distance = buf.get_u16_le();
5785 let tmp = buf.get_u8();
5786 __struct.sensor_type =
5787 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5788 enum_type: "MavDistanceSensor",
5789 value: tmp as u32,
5790 })?;
5791 __struct.increment = buf.get_u8();
5792 __struct.increment_f = buf.get_f32_le();
5793 __struct.angle_offset = buf.get_f32_le();
5794 let tmp = buf.get_u8();
5795 __struct.frame =
5796 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
5797 enum_type: "MavFrame",
5798 value: tmp as u32,
5799 })?;
5800 Ok(__struct)
5801 }
5802 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5803 let mut __tmp = BytesMut::new(bytes);
5804 #[allow(clippy::absurd_extreme_comparisons)]
5805 #[allow(unused_comparisons)]
5806 if __tmp.remaining() < Self::ENCODED_LEN {
5807 panic!(
5808 "buffer is too small (need {} bytes, but got {})",
5809 Self::ENCODED_LEN,
5810 __tmp.remaining(),
5811 )
5812 }
5813 __tmp.put_u64_le(self.time_usec);
5814 for val in &self.distances {
5815 __tmp.put_u16_le(*val);
5816 }
5817 __tmp.put_u16_le(self.min_distance);
5818 __tmp.put_u16_le(self.max_distance);
5819 __tmp.put_u8(self.sensor_type as u8);
5820 __tmp.put_u8(self.increment);
5821 __tmp.put_f32_le(self.increment_f);
5822 __tmp.put_f32_le(self.angle_offset);
5823 __tmp.put_u8(self.frame as u8);
5824 if matches!(version, MavlinkVersion::V2) {
5825 let len = __tmp.len();
5826 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
5827 } else {
5828 __tmp.len()
5829 }
5830 }
5831}
5832#[doc = "id: 332"]
5833#[doc = "Describe a trajectory using an array of up-to 5 waypoints in the local frame (MAV_FRAME_LOCAL_NED)."]
5834#[derive(Debug, Clone, PartialEq)]
5835#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
5836#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
5837pub struct TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
5838 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
5839 pub time_usec: u64,
5840 #[doc = "X-coordinate of waypoint, set to NaN if not being used"]
5841 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5842 pub pos_x: [f32; 5],
5843 #[doc = "Y-coordinate of waypoint, set to NaN if not being used"]
5844 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5845 pub pos_y: [f32; 5],
5846 #[doc = "Z-coordinate of waypoint, set to NaN if not being used"]
5847 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5848 pub pos_z: [f32; 5],
5849 #[doc = "X-velocity of waypoint, set to NaN if not being used"]
5850 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5851 pub vel_x: [f32; 5],
5852 #[doc = "Y-velocity of waypoint, set to NaN if not being used"]
5853 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5854 pub vel_y: [f32; 5],
5855 #[doc = "Z-velocity of waypoint, set to NaN if not being used"]
5856 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5857 pub vel_z: [f32; 5],
5858 #[doc = "X-acceleration of waypoint, set to NaN if not being used"]
5859 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5860 pub acc_x: [f32; 5],
5861 #[doc = "Y-acceleration of waypoint, set to NaN if not being used"]
5862 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5863 pub acc_y: [f32; 5],
5864 #[doc = "Z-acceleration of waypoint, set to NaN if not being used"]
5865 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5866 pub acc_z: [f32; 5],
5867 #[doc = "Yaw angle, set to NaN if not being used"]
5868 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5869 pub pos_yaw: [f32; 5],
5870 #[doc = "Yaw rate, set to NaN if not being used"]
5871 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5872 pub vel_yaw: [f32; 5],
5873 #[doc = "MAV_CMD command id of waypoint, set to UINT16_MAX if not being used."]
5874 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
5875 pub command: [u16; 5],
5876 #[doc = "Number of valid points (up-to 5 waypoints are possible)"]
5877 pub valid_points: u8,
5878}
5879impl TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
5880 pub const ENCODED_LEN: usize = 239usize;
5881 pub const DEFAULT: Self = Self {
5882 time_usec: 0_u64,
5883 pos_x: [0.0_f32; 5usize],
5884 pos_y: [0.0_f32; 5usize],
5885 pos_z: [0.0_f32; 5usize],
5886 vel_x: [0.0_f32; 5usize],
5887 vel_y: [0.0_f32; 5usize],
5888 vel_z: [0.0_f32; 5usize],
5889 acc_x: [0.0_f32; 5usize],
5890 acc_y: [0.0_f32; 5usize],
5891 acc_z: [0.0_f32; 5usize],
5892 pos_yaw: [0.0_f32; 5usize],
5893 vel_yaw: [0.0_f32; 5usize],
5894 command: [0_u16; 5usize],
5895 valid_points: 0_u8,
5896 };
5897 #[cfg(feature = "arbitrary")]
5898 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
5899 use arbitrary::{Arbitrary, Unstructured};
5900 let mut buf = [0u8; 1024];
5901 rng.fill_bytes(&mut buf);
5902 let mut unstructured = Unstructured::new(&buf);
5903 Self::arbitrary(&mut unstructured).unwrap_or_default()
5904 }
5905}
5906impl Default for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
5907 fn default() -> Self {
5908 Self::DEFAULT.clone()
5909 }
5910}
5911impl MessageData for TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA {
5912 type Message = MavMessage;
5913 const ID: u32 = 332u32;
5914 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_WAYPOINTS";
5915 const EXTRA_CRC: u8 = 236u8;
5916 const ENCODED_LEN: usize = 239usize;
5917 fn deser(
5918 _version: MavlinkVersion,
5919 __input: &[u8],
5920 ) -> Result<Self, ::mavlink_core::error::ParserError> {
5921 let avail_len = __input.len();
5922 let mut payload_buf = [0; Self::ENCODED_LEN];
5923 let mut buf = if avail_len < Self::ENCODED_LEN {
5924 payload_buf[0..avail_len].copy_from_slice(__input);
5925 Bytes::new(&payload_buf)
5926 } else {
5927 Bytes::new(__input)
5928 };
5929 let mut __struct = Self::default();
5930 __struct.time_usec = buf.get_u64_le();
5931 for v in &mut __struct.pos_x {
5932 let val = buf.get_f32_le();
5933 *v = val;
5934 }
5935 for v in &mut __struct.pos_y {
5936 let val = buf.get_f32_le();
5937 *v = val;
5938 }
5939 for v in &mut __struct.pos_z {
5940 let val = buf.get_f32_le();
5941 *v = val;
5942 }
5943 for v in &mut __struct.vel_x {
5944 let val = buf.get_f32_le();
5945 *v = val;
5946 }
5947 for v in &mut __struct.vel_y {
5948 let val = buf.get_f32_le();
5949 *v = val;
5950 }
5951 for v in &mut __struct.vel_z {
5952 let val = buf.get_f32_le();
5953 *v = val;
5954 }
5955 for v in &mut __struct.acc_x {
5956 let val = buf.get_f32_le();
5957 *v = val;
5958 }
5959 for v in &mut __struct.acc_y {
5960 let val = buf.get_f32_le();
5961 *v = val;
5962 }
5963 for v in &mut __struct.acc_z {
5964 let val = buf.get_f32_le();
5965 *v = val;
5966 }
5967 for v in &mut __struct.pos_yaw {
5968 let val = buf.get_f32_le();
5969 *v = val;
5970 }
5971 for v in &mut __struct.vel_yaw {
5972 let val = buf.get_f32_le();
5973 *v = val;
5974 }
5975 for v in &mut __struct.command {
5976 let val = buf.get_u16_le();
5977 *v = val;
5978 }
5979 __struct.valid_points = buf.get_u8();
5980 Ok(__struct)
5981 }
5982 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
5983 let mut __tmp = BytesMut::new(bytes);
5984 #[allow(clippy::absurd_extreme_comparisons)]
5985 #[allow(unused_comparisons)]
5986 if __tmp.remaining() < Self::ENCODED_LEN {
5987 panic!(
5988 "buffer is too small (need {} bytes, but got {})",
5989 Self::ENCODED_LEN,
5990 __tmp.remaining(),
5991 )
5992 }
5993 __tmp.put_u64_le(self.time_usec);
5994 for val in &self.pos_x {
5995 __tmp.put_f32_le(*val);
5996 }
5997 for val in &self.pos_y {
5998 __tmp.put_f32_le(*val);
5999 }
6000 for val in &self.pos_z {
6001 __tmp.put_f32_le(*val);
6002 }
6003 for val in &self.vel_x {
6004 __tmp.put_f32_le(*val);
6005 }
6006 for val in &self.vel_y {
6007 __tmp.put_f32_le(*val);
6008 }
6009 for val in &self.vel_z {
6010 __tmp.put_f32_le(*val);
6011 }
6012 for val in &self.acc_x {
6013 __tmp.put_f32_le(*val);
6014 }
6015 for val in &self.acc_y {
6016 __tmp.put_f32_le(*val);
6017 }
6018 for val in &self.acc_z {
6019 __tmp.put_f32_le(*val);
6020 }
6021 for val in &self.pos_yaw {
6022 __tmp.put_f32_le(*val);
6023 }
6024 for val in &self.vel_yaw {
6025 __tmp.put_f32_le(*val);
6026 }
6027 for val in &self.command {
6028 __tmp.put_u16_le(*val);
6029 }
6030 __tmp.put_u8(self.valid_points);
6031 if matches!(version, MavlinkVersion::V2) {
6032 let len = __tmp.len();
6033 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6034 } else {
6035 __tmp.len()
6036 }
6037 }
6038}
6039#[doc = "id: 286"]
6040#[doc = "Low level message containing autopilot state relevant for a gimbal device. This message is to be sent from the autopilot to the gimbal device component. The data of this message are for the gimbal device's estimator corrections, in particular horizon compensation, as well as indicates autopilot control intentions, e.g. feed forward angular control in the z-axis."]
6041#[derive(Debug, Clone, PartialEq)]
6042#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6043#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6044pub struct AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
6045 #[doc = "Timestamp (time since system boot)."]
6046 pub time_boot_us: u64,
6047 #[doc = "Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention)."]
6048 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6049 pub q: [f32; 4],
6050 #[doc = "Estimated delay of the attitude data. 0 if unknown."]
6051 pub q_estimated_delay_us: u32,
6052 #[doc = "X Speed in NED (North, East, Down). NAN if unknown."]
6053 pub vx: f32,
6054 #[doc = "Y Speed in NED (North, East, Down). NAN if unknown."]
6055 pub vy: f32,
6056 #[doc = "Z Speed in NED (North, East, Down). NAN if unknown."]
6057 pub vz: f32,
6058 #[doc = "Estimated delay of the speed data. 0 if unknown."]
6059 pub v_estimated_delay_us: u32,
6060 #[doc = "Feed forward Z component of angular velocity (positive: yawing to the right). NaN to be ignored. This is to indicate if the autopilot is actively yawing."]
6061 pub feed_forward_angular_velocity_z: f32,
6062 #[doc = "Bitmap indicating which estimator outputs are valid."]
6063 pub estimator_status: EstimatorStatusFlags,
6064 #[doc = "System ID"]
6065 pub target_system: u8,
6066 #[doc = "Component ID"]
6067 pub target_component: u8,
6068 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
6069 pub landed_state: MavLandedState,
6070 #[doc = "Z component of angular velocity in NED (North, East, Down). NaN if unknown."]
6071 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6072 pub angular_velocity_z: f32,
6073}
6074impl AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
6075 pub const ENCODED_LEN: usize = 57usize;
6076 pub const DEFAULT: Self = Self {
6077 time_boot_us: 0_u64,
6078 q: [0.0_f32; 4usize],
6079 q_estimated_delay_us: 0_u32,
6080 vx: 0.0_f32,
6081 vy: 0.0_f32,
6082 vz: 0.0_f32,
6083 v_estimated_delay_us: 0_u32,
6084 feed_forward_angular_velocity_z: 0.0_f32,
6085 estimator_status: EstimatorStatusFlags::DEFAULT,
6086 target_system: 0_u8,
6087 target_component: 0_u8,
6088 landed_state: MavLandedState::DEFAULT,
6089 angular_velocity_z: 0.0_f32,
6090 };
6091 #[cfg(feature = "arbitrary")]
6092 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6093 use arbitrary::{Arbitrary, Unstructured};
6094 let mut buf = [0u8; 1024];
6095 rng.fill_bytes(&mut buf);
6096 let mut unstructured = Unstructured::new(&buf);
6097 Self::arbitrary(&mut unstructured).unwrap_or_default()
6098 }
6099}
6100impl Default for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
6101 fn default() -> Self {
6102 Self::DEFAULT.clone()
6103 }
6104}
6105impl MessageData for AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA {
6106 type Message = MavMessage;
6107 const ID: u32 = 286u32;
6108 const NAME: &'static str = "AUTOPILOT_STATE_FOR_GIMBAL_DEVICE";
6109 const EXTRA_CRC: u8 = 210u8;
6110 const ENCODED_LEN: usize = 57usize;
6111 fn deser(
6112 _version: MavlinkVersion,
6113 __input: &[u8],
6114 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6115 let avail_len = __input.len();
6116 let mut payload_buf = [0; Self::ENCODED_LEN];
6117 let mut buf = if avail_len < Self::ENCODED_LEN {
6118 payload_buf[0..avail_len].copy_from_slice(__input);
6119 Bytes::new(&payload_buf)
6120 } else {
6121 Bytes::new(__input)
6122 };
6123 let mut __struct = Self::default();
6124 __struct.time_boot_us = buf.get_u64_le();
6125 for v in &mut __struct.q {
6126 let val = buf.get_f32_le();
6127 *v = val;
6128 }
6129 __struct.q_estimated_delay_us = buf.get_u32_le();
6130 __struct.vx = buf.get_f32_le();
6131 __struct.vy = buf.get_f32_le();
6132 __struct.vz = buf.get_f32_le();
6133 __struct.v_estimated_delay_us = buf.get_u32_le();
6134 __struct.feed_forward_angular_velocity_z = buf.get_f32_le();
6135 let tmp = buf.get_u16_le();
6136 __struct.estimator_status = EstimatorStatusFlags::from_bits(
6137 tmp & EstimatorStatusFlags::all().bits(),
6138 )
6139 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6140 flag_type: "EstimatorStatusFlags",
6141 value: tmp as u32,
6142 })?;
6143 __struct.target_system = buf.get_u8();
6144 __struct.target_component = buf.get_u8();
6145 let tmp = buf.get_u8();
6146 __struct.landed_state =
6147 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6148 enum_type: "MavLandedState",
6149 value: tmp as u32,
6150 })?;
6151 __struct.angular_velocity_z = buf.get_f32_le();
6152 Ok(__struct)
6153 }
6154 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6155 let mut __tmp = BytesMut::new(bytes);
6156 #[allow(clippy::absurd_extreme_comparisons)]
6157 #[allow(unused_comparisons)]
6158 if __tmp.remaining() < Self::ENCODED_LEN {
6159 panic!(
6160 "buffer is too small (need {} bytes, but got {})",
6161 Self::ENCODED_LEN,
6162 __tmp.remaining(),
6163 )
6164 }
6165 __tmp.put_u64_le(self.time_boot_us);
6166 for val in &self.q {
6167 __tmp.put_f32_le(*val);
6168 }
6169 __tmp.put_u32_le(self.q_estimated_delay_us);
6170 __tmp.put_f32_le(self.vx);
6171 __tmp.put_f32_le(self.vy);
6172 __tmp.put_f32_le(self.vz);
6173 __tmp.put_u32_le(self.v_estimated_delay_us);
6174 __tmp.put_f32_le(self.feed_forward_angular_velocity_z);
6175 __tmp.put_u16_le(self.estimator_status.bits());
6176 __tmp.put_u8(self.target_system);
6177 __tmp.put_u8(self.target_component);
6178 __tmp.put_u8(self.landed_state as u8);
6179 __tmp.put_f32_le(self.angular_velocity_z);
6180 if matches!(version, MavlinkVersion::V2) {
6181 let len = __tmp.len();
6182 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6183 } else {
6184 __tmp.len()
6185 }
6186 }
6187}
6188#[doc = "id: 263"]
6189#[doc = "Information about a captured image. This is emitted every time a message is captured. MAV_CMD_REQUEST_MESSAGE can be used to (re)request this message for a specific sequence number or range of sequence numbers: MAV_CMD_REQUEST_MESSAGE.param2 indicates the sequence number the first image to send, or set to -1 to send the message for all sequence numbers. MAV_CMD_REQUEST_MESSAGE.param3 is used to specify a range of messages to send: set to 0 (default) to send just the the message for the sequence number in param 2, set to -1 to send the message for the sequence number in param 2 and all the following sequence numbers, set to the sequence number of the final message in the range."]
6190#[derive(Debug, Clone, PartialEq)]
6191#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6192#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6193pub struct CAMERA_IMAGE_CAPTURED_DATA {
6194 #[doc = "Timestamp (time since UNIX epoch) in UTC. 0 for unknown."]
6195 pub time_utc: u64,
6196 #[doc = "Timestamp (time since system boot)."]
6197 pub time_boot_ms: u32,
6198 #[doc = "Latitude where image was taken"]
6199 pub lat: i32,
6200 #[doc = "Longitude where capture was taken"]
6201 pub lon: i32,
6202 #[doc = "Altitude (MSL) where image was taken"]
6203 pub alt: i32,
6204 #[doc = "Altitude above ground"]
6205 pub relative_alt: i32,
6206 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
6207 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6208 pub q: [f32; 4],
6209 #[doc = "Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)"]
6210 pub image_index: i32,
6211 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). Field name is usually camera_device_id."]
6212 pub camera_id: u8,
6213 #[doc = "Boolean indicating success (1) or failure (0) while capturing this image."]
6214 pub capture_result: i8,
6215 #[doc = "URL of image taken. Either local storage or <http://foo.jpg> if camera provides an HTTP interface."]
6216 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6217 pub file_url: [u8; 205],
6218}
6219impl CAMERA_IMAGE_CAPTURED_DATA {
6220 pub const ENCODED_LEN: usize = 255usize;
6221 pub const DEFAULT: Self = Self {
6222 time_utc: 0_u64,
6223 time_boot_ms: 0_u32,
6224 lat: 0_i32,
6225 lon: 0_i32,
6226 alt: 0_i32,
6227 relative_alt: 0_i32,
6228 q: [0.0_f32; 4usize],
6229 image_index: 0_i32,
6230 camera_id: 0_u8,
6231 capture_result: 0_i8,
6232 file_url: [0_u8; 205usize],
6233 };
6234 #[cfg(feature = "arbitrary")]
6235 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6236 use arbitrary::{Arbitrary, Unstructured};
6237 let mut buf = [0u8; 1024];
6238 rng.fill_bytes(&mut buf);
6239 let mut unstructured = Unstructured::new(&buf);
6240 Self::arbitrary(&mut unstructured).unwrap_or_default()
6241 }
6242}
6243impl Default for CAMERA_IMAGE_CAPTURED_DATA {
6244 fn default() -> Self {
6245 Self::DEFAULT.clone()
6246 }
6247}
6248impl MessageData for CAMERA_IMAGE_CAPTURED_DATA {
6249 type Message = MavMessage;
6250 const ID: u32 = 263u32;
6251 const NAME: &'static str = "CAMERA_IMAGE_CAPTURED";
6252 const EXTRA_CRC: u8 = 133u8;
6253 const ENCODED_LEN: usize = 255usize;
6254 fn deser(
6255 _version: MavlinkVersion,
6256 __input: &[u8],
6257 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6258 let avail_len = __input.len();
6259 let mut payload_buf = [0; Self::ENCODED_LEN];
6260 let mut buf = if avail_len < Self::ENCODED_LEN {
6261 payload_buf[0..avail_len].copy_from_slice(__input);
6262 Bytes::new(&payload_buf)
6263 } else {
6264 Bytes::new(__input)
6265 };
6266 let mut __struct = Self::default();
6267 __struct.time_utc = buf.get_u64_le();
6268 __struct.time_boot_ms = buf.get_u32_le();
6269 __struct.lat = buf.get_i32_le();
6270 __struct.lon = buf.get_i32_le();
6271 __struct.alt = buf.get_i32_le();
6272 __struct.relative_alt = buf.get_i32_le();
6273 for v in &mut __struct.q {
6274 let val = buf.get_f32_le();
6275 *v = val;
6276 }
6277 __struct.image_index = buf.get_i32_le();
6278 __struct.camera_id = buf.get_u8();
6279 __struct.capture_result = buf.get_i8();
6280 for v in &mut __struct.file_url {
6281 let val = buf.get_u8();
6282 *v = val;
6283 }
6284 Ok(__struct)
6285 }
6286 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6287 let mut __tmp = BytesMut::new(bytes);
6288 #[allow(clippy::absurd_extreme_comparisons)]
6289 #[allow(unused_comparisons)]
6290 if __tmp.remaining() < Self::ENCODED_LEN {
6291 panic!(
6292 "buffer is too small (need {} bytes, but got {})",
6293 Self::ENCODED_LEN,
6294 __tmp.remaining(),
6295 )
6296 }
6297 __tmp.put_u64_le(self.time_utc);
6298 __tmp.put_u32_le(self.time_boot_ms);
6299 __tmp.put_i32_le(self.lat);
6300 __tmp.put_i32_le(self.lon);
6301 __tmp.put_i32_le(self.alt);
6302 __tmp.put_i32_le(self.relative_alt);
6303 for val in &self.q {
6304 __tmp.put_f32_le(*val);
6305 }
6306 __tmp.put_i32_le(self.image_index);
6307 __tmp.put_u8(self.camera_id);
6308 __tmp.put_i8(self.capture_result);
6309 for val in &self.file_url {
6310 __tmp.put_u8(*val);
6311 }
6312 if matches!(version, MavlinkVersion::V2) {
6313 let len = __tmp.len();
6314 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6315 } else {
6316 __tmp.len()
6317 }
6318 }
6319}
6320#[doc = "id: 300"]
6321#[doc = "Version and capability of protocol version. This message can be requested with MAV_CMD_REQUEST_MESSAGE and is used as part of the handshaking to establish which MAVLink version should be used on the network. Every node should respond to a request for PROTOCOL_VERSION to enable the handshaking. Library implementers should consider adding this into the default decoding state machine to allow the protocol core to respond directly."]
6322#[derive(Debug, Clone, PartialEq)]
6323#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6324#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6325pub struct PROTOCOL_VERSION_DATA {
6326 #[doc = "Currently active MAVLink version number * 100: v1.0 is 100, v2.0 is 200, etc."]
6327 pub version: u16,
6328 #[doc = "Minimum MAVLink version supported"]
6329 pub min_version: u16,
6330 #[doc = "Maximum MAVLink version supported (set to the same value as version by default)"]
6331 pub max_version: u16,
6332 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
6333 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6334 pub spec_version_hash: [u8; 8],
6335 #[doc = "The first 8 bytes (not characters printed in hex!) of the git hash."]
6336 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6337 pub library_version_hash: [u8; 8],
6338}
6339impl PROTOCOL_VERSION_DATA {
6340 pub const ENCODED_LEN: usize = 22usize;
6341 pub const DEFAULT: Self = Self {
6342 version: 0_u16,
6343 min_version: 0_u16,
6344 max_version: 0_u16,
6345 spec_version_hash: [0_u8; 8usize],
6346 library_version_hash: [0_u8; 8usize],
6347 };
6348 #[cfg(feature = "arbitrary")]
6349 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6350 use arbitrary::{Arbitrary, Unstructured};
6351 let mut buf = [0u8; 1024];
6352 rng.fill_bytes(&mut buf);
6353 let mut unstructured = Unstructured::new(&buf);
6354 Self::arbitrary(&mut unstructured).unwrap_or_default()
6355 }
6356}
6357impl Default for PROTOCOL_VERSION_DATA {
6358 fn default() -> Self {
6359 Self::DEFAULT.clone()
6360 }
6361}
6362impl MessageData for PROTOCOL_VERSION_DATA {
6363 type Message = MavMessage;
6364 const ID: u32 = 300u32;
6365 const NAME: &'static str = "PROTOCOL_VERSION";
6366 const EXTRA_CRC: u8 = 217u8;
6367 const ENCODED_LEN: usize = 22usize;
6368 fn deser(
6369 _version: MavlinkVersion,
6370 __input: &[u8],
6371 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6372 let avail_len = __input.len();
6373 let mut payload_buf = [0; Self::ENCODED_LEN];
6374 let mut buf = if avail_len < Self::ENCODED_LEN {
6375 payload_buf[0..avail_len].copy_from_slice(__input);
6376 Bytes::new(&payload_buf)
6377 } else {
6378 Bytes::new(__input)
6379 };
6380 let mut __struct = Self::default();
6381 __struct.version = buf.get_u16_le();
6382 __struct.min_version = buf.get_u16_le();
6383 __struct.max_version = buf.get_u16_le();
6384 for v in &mut __struct.spec_version_hash {
6385 let val = buf.get_u8();
6386 *v = val;
6387 }
6388 for v in &mut __struct.library_version_hash {
6389 let val = buf.get_u8();
6390 *v = val;
6391 }
6392 Ok(__struct)
6393 }
6394 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6395 let mut __tmp = BytesMut::new(bytes);
6396 #[allow(clippy::absurd_extreme_comparisons)]
6397 #[allow(unused_comparisons)]
6398 if __tmp.remaining() < Self::ENCODED_LEN {
6399 panic!(
6400 "buffer is too small (need {} bytes, but got {})",
6401 Self::ENCODED_LEN,
6402 __tmp.remaining(),
6403 )
6404 }
6405 __tmp.put_u16_le(self.version);
6406 __tmp.put_u16_le(self.min_version);
6407 __tmp.put_u16_le(self.max_version);
6408 for val in &self.spec_version_hash {
6409 __tmp.put_u8(*val);
6410 }
6411 for val in &self.library_version_hash {
6412 __tmp.put_u8(*val);
6413 }
6414 if matches!(version, MavlinkVersion::V2) {
6415 let len = __tmp.len();
6416 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6417 } else {
6418 __tmp.len()
6419 }
6420 }
6421}
6422#[doc = "id: 124"]
6423#[doc = "Second GPS data."]
6424#[derive(Debug, Clone, PartialEq)]
6425#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6426#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6427pub struct GPS2_RAW_DATA {
6428 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
6429 pub time_usec: u64,
6430 #[doc = "Latitude (WGS84)"]
6431 pub lat: i32,
6432 #[doc = "Longitude (WGS84)"]
6433 pub lon: i32,
6434 #[doc = "Altitude (MSL). Positive for up."]
6435 pub alt: i32,
6436 #[doc = "Age of DGPS info"]
6437 pub dgps_age: u32,
6438 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
6439 pub eph: u16,
6440 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
6441 pub epv: u16,
6442 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
6443 pub vel: u16,
6444 #[doc = "Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
6445 pub cog: u16,
6446 #[doc = "GPS fix type."]
6447 pub fix_type: GpsFixType,
6448 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
6449 pub satellites_visible: u8,
6450 #[doc = "Number of DGPS satellites"]
6451 pub dgps_numch: u8,
6452 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
6453 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6454 pub yaw: u16,
6455 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
6456 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6457 pub alt_ellipsoid: i32,
6458 #[doc = "Position uncertainty."]
6459 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6460 pub h_acc: u32,
6461 #[doc = "Altitude uncertainty."]
6462 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6463 pub v_acc: u32,
6464 #[doc = "Speed uncertainty."]
6465 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6466 pub vel_acc: u32,
6467 #[doc = "Heading / track uncertainty"]
6468 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6469 pub hdg_acc: u32,
6470}
6471impl GPS2_RAW_DATA {
6472 pub const ENCODED_LEN: usize = 57usize;
6473 pub const DEFAULT: Self = Self {
6474 time_usec: 0_u64,
6475 lat: 0_i32,
6476 lon: 0_i32,
6477 alt: 0_i32,
6478 dgps_age: 0_u32,
6479 eph: 0_u16,
6480 epv: 0_u16,
6481 vel: 0_u16,
6482 cog: 0_u16,
6483 fix_type: GpsFixType::DEFAULT,
6484 satellites_visible: 0_u8,
6485 dgps_numch: 0_u8,
6486 yaw: 0_u16,
6487 alt_ellipsoid: 0_i32,
6488 h_acc: 0_u32,
6489 v_acc: 0_u32,
6490 vel_acc: 0_u32,
6491 hdg_acc: 0_u32,
6492 };
6493 #[cfg(feature = "arbitrary")]
6494 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6495 use arbitrary::{Arbitrary, Unstructured};
6496 let mut buf = [0u8; 1024];
6497 rng.fill_bytes(&mut buf);
6498 let mut unstructured = Unstructured::new(&buf);
6499 Self::arbitrary(&mut unstructured).unwrap_or_default()
6500 }
6501}
6502impl Default for GPS2_RAW_DATA {
6503 fn default() -> Self {
6504 Self::DEFAULT.clone()
6505 }
6506}
6507impl MessageData for GPS2_RAW_DATA {
6508 type Message = MavMessage;
6509 const ID: u32 = 124u32;
6510 const NAME: &'static str = "GPS2_RAW";
6511 const EXTRA_CRC: u8 = 87u8;
6512 const ENCODED_LEN: usize = 57usize;
6513 fn deser(
6514 _version: MavlinkVersion,
6515 __input: &[u8],
6516 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6517 let avail_len = __input.len();
6518 let mut payload_buf = [0; Self::ENCODED_LEN];
6519 let mut buf = if avail_len < Self::ENCODED_LEN {
6520 payload_buf[0..avail_len].copy_from_slice(__input);
6521 Bytes::new(&payload_buf)
6522 } else {
6523 Bytes::new(__input)
6524 };
6525 let mut __struct = Self::default();
6526 __struct.time_usec = buf.get_u64_le();
6527 __struct.lat = buf.get_i32_le();
6528 __struct.lon = buf.get_i32_le();
6529 __struct.alt = buf.get_i32_le();
6530 __struct.dgps_age = buf.get_u32_le();
6531 __struct.eph = buf.get_u16_le();
6532 __struct.epv = buf.get_u16_le();
6533 __struct.vel = buf.get_u16_le();
6534 __struct.cog = buf.get_u16_le();
6535 let tmp = buf.get_u8();
6536 __struct.fix_type =
6537 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6538 enum_type: "GpsFixType",
6539 value: tmp as u32,
6540 })?;
6541 __struct.satellites_visible = buf.get_u8();
6542 __struct.dgps_numch = buf.get_u8();
6543 __struct.yaw = buf.get_u16_le();
6544 __struct.alt_ellipsoid = buf.get_i32_le();
6545 __struct.h_acc = buf.get_u32_le();
6546 __struct.v_acc = buf.get_u32_le();
6547 __struct.vel_acc = buf.get_u32_le();
6548 __struct.hdg_acc = buf.get_u32_le();
6549 Ok(__struct)
6550 }
6551 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6552 let mut __tmp = BytesMut::new(bytes);
6553 #[allow(clippy::absurd_extreme_comparisons)]
6554 #[allow(unused_comparisons)]
6555 if __tmp.remaining() < Self::ENCODED_LEN {
6556 panic!(
6557 "buffer is too small (need {} bytes, but got {})",
6558 Self::ENCODED_LEN,
6559 __tmp.remaining(),
6560 )
6561 }
6562 __tmp.put_u64_le(self.time_usec);
6563 __tmp.put_i32_le(self.lat);
6564 __tmp.put_i32_le(self.lon);
6565 __tmp.put_i32_le(self.alt);
6566 __tmp.put_u32_le(self.dgps_age);
6567 __tmp.put_u16_le(self.eph);
6568 __tmp.put_u16_le(self.epv);
6569 __tmp.put_u16_le(self.vel);
6570 __tmp.put_u16_le(self.cog);
6571 __tmp.put_u8(self.fix_type as u8);
6572 __tmp.put_u8(self.satellites_visible);
6573 __tmp.put_u8(self.dgps_numch);
6574 __tmp.put_u16_le(self.yaw);
6575 __tmp.put_i32_le(self.alt_ellipsoid);
6576 __tmp.put_u32_le(self.h_acc);
6577 __tmp.put_u32_le(self.v_acc);
6578 __tmp.put_u32_le(self.vel_acc);
6579 __tmp.put_u32_le(self.hdg_acc);
6580 if matches!(version, MavlinkVersion::V2) {
6581 let len = __tmp.len();
6582 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6583 } else {
6584 __tmp.len()
6585 }
6586 }
6587}
6588#[doc = "id: 340"]
6589#[doc = "The global position resulting from GPS and sensor fusion."]
6590#[derive(Debug, Clone, PartialEq)]
6591#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6592#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6593pub struct UTM_GLOBAL_POSITION_DATA {
6594 #[doc = "Time of applicability of position (microseconds since UNIX epoch)."]
6595 pub time: u64,
6596 #[doc = "Latitude (WGS84)"]
6597 pub lat: i32,
6598 #[doc = "Longitude (WGS84)"]
6599 pub lon: i32,
6600 #[doc = "Altitude (WGS84)"]
6601 pub alt: i32,
6602 #[doc = "Altitude above ground"]
6603 pub relative_alt: i32,
6604 #[doc = "Next waypoint, latitude (WGS84)"]
6605 pub next_lat: i32,
6606 #[doc = "Next waypoint, longitude (WGS84)"]
6607 pub next_lon: i32,
6608 #[doc = "Next waypoint, altitude (WGS84)"]
6609 pub next_alt: i32,
6610 #[doc = "Ground X speed (latitude, positive north)"]
6611 pub vx: i16,
6612 #[doc = "Ground Y speed (longitude, positive east)"]
6613 pub vy: i16,
6614 #[doc = "Ground Z speed (altitude, positive down)"]
6615 pub vz: i16,
6616 #[doc = "Horizontal position uncertainty (standard deviation)"]
6617 pub h_acc: u16,
6618 #[doc = "Altitude uncertainty (standard deviation)"]
6619 pub v_acc: u16,
6620 #[doc = "Speed uncertainty (standard deviation)"]
6621 pub vel_acc: u16,
6622 #[doc = "Time until next update. Set to 0 if unknown or in data driven mode."]
6623 pub update_rate: u16,
6624 #[doc = "Unique UAS ID."]
6625 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
6626 pub uas_id: [u8; 18],
6627 #[doc = "Flight state"]
6628 pub flight_state: UtmFlightState,
6629 #[doc = "Bitwise OR combination of the data available flags."]
6630 pub flags: UtmDataAvailFlags,
6631}
6632impl UTM_GLOBAL_POSITION_DATA {
6633 pub const ENCODED_LEN: usize = 70usize;
6634 pub const DEFAULT: Self = Self {
6635 time: 0_u64,
6636 lat: 0_i32,
6637 lon: 0_i32,
6638 alt: 0_i32,
6639 relative_alt: 0_i32,
6640 next_lat: 0_i32,
6641 next_lon: 0_i32,
6642 next_alt: 0_i32,
6643 vx: 0_i16,
6644 vy: 0_i16,
6645 vz: 0_i16,
6646 h_acc: 0_u16,
6647 v_acc: 0_u16,
6648 vel_acc: 0_u16,
6649 update_rate: 0_u16,
6650 uas_id: [0_u8; 18usize],
6651 flight_state: UtmFlightState::DEFAULT,
6652 flags: UtmDataAvailFlags::DEFAULT,
6653 };
6654 #[cfg(feature = "arbitrary")]
6655 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6656 use arbitrary::{Arbitrary, Unstructured};
6657 let mut buf = [0u8; 1024];
6658 rng.fill_bytes(&mut buf);
6659 let mut unstructured = Unstructured::new(&buf);
6660 Self::arbitrary(&mut unstructured).unwrap_or_default()
6661 }
6662}
6663impl Default for UTM_GLOBAL_POSITION_DATA {
6664 fn default() -> Self {
6665 Self::DEFAULT.clone()
6666 }
6667}
6668impl MessageData for UTM_GLOBAL_POSITION_DATA {
6669 type Message = MavMessage;
6670 const ID: u32 = 340u32;
6671 const NAME: &'static str = "UTM_GLOBAL_POSITION";
6672 const EXTRA_CRC: u8 = 99u8;
6673 const ENCODED_LEN: usize = 70usize;
6674 fn deser(
6675 _version: MavlinkVersion,
6676 __input: &[u8],
6677 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6678 let avail_len = __input.len();
6679 let mut payload_buf = [0; Self::ENCODED_LEN];
6680 let mut buf = if avail_len < Self::ENCODED_LEN {
6681 payload_buf[0..avail_len].copy_from_slice(__input);
6682 Bytes::new(&payload_buf)
6683 } else {
6684 Bytes::new(__input)
6685 };
6686 let mut __struct = Self::default();
6687 __struct.time = buf.get_u64_le();
6688 __struct.lat = buf.get_i32_le();
6689 __struct.lon = buf.get_i32_le();
6690 __struct.alt = buf.get_i32_le();
6691 __struct.relative_alt = buf.get_i32_le();
6692 __struct.next_lat = buf.get_i32_le();
6693 __struct.next_lon = buf.get_i32_le();
6694 __struct.next_alt = buf.get_i32_le();
6695 __struct.vx = buf.get_i16_le();
6696 __struct.vy = buf.get_i16_le();
6697 __struct.vz = buf.get_i16_le();
6698 __struct.h_acc = buf.get_u16_le();
6699 __struct.v_acc = buf.get_u16_le();
6700 __struct.vel_acc = buf.get_u16_le();
6701 __struct.update_rate = buf.get_u16_le();
6702 for v in &mut __struct.uas_id {
6703 let val = buf.get_u8();
6704 *v = val;
6705 }
6706 let tmp = buf.get_u8();
6707 __struct.flight_state =
6708 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
6709 enum_type: "UtmFlightState",
6710 value: tmp as u32,
6711 })?;
6712 let tmp = buf.get_u8();
6713 __struct.flags = UtmDataAvailFlags::from_bits(tmp & UtmDataAvailFlags::all().bits())
6714 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
6715 flag_type: "UtmDataAvailFlags",
6716 value: tmp as u32,
6717 })?;
6718 Ok(__struct)
6719 }
6720 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6721 let mut __tmp = BytesMut::new(bytes);
6722 #[allow(clippy::absurd_extreme_comparisons)]
6723 #[allow(unused_comparisons)]
6724 if __tmp.remaining() < Self::ENCODED_LEN {
6725 panic!(
6726 "buffer is too small (need {} bytes, but got {})",
6727 Self::ENCODED_LEN,
6728 __tmp.remaining(),
6729 )
6730 }
6731 __tmp.put_u64_le(self.time);
6732 __tmp.put_i32_le(self.lat);
6733 __tmp.put_i32_le(self.lon);
6734 __tmp.put_i32_le(self.alt);
6735 __tmp.put_i32_le(self.relative_alt);
6736 __tmp.put_i32_le(self.next_lat);
6737 __tmp.put_i32_le(self.next_lon);
6738 __tmp.put_i32_le(self.next_alt);
6739 __tmp.put_i16_le(self.vx);
6740 __tmp.put_i16_le(self.vy);
6741 __tmp.put_i16_le(self.vz);
6742 __tmp.put_u16_le(self.h_acc);
6743 __tmp.put_u16_le(self.v_acc);
6744 __tmp.put_u16_le(self.vel_acc);
6745 __tmp.put_u16_le(self.update_rate);
6746 for val in &self.uas_id {
6747 __tmp.put_u8(*val);
6748 }
6749 __tmp.put_u8(self.flight_state as u8);
6750 __tmp.put_u8(self.flags.bits());
6751 if matches!(version, MavlinkVersion::V2) {
6752 let len = __tmp.len();
6753 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6754 } else {
6755 __tmp.len()
6756 }
6757 }
6758}
6759#[doc = "id: 113"]
6760#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
6761#[derive(Debug, Clone, PartialEq)]
6762#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6763#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6764pub struct HIL_GPS_DATA {
6765 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
6766 pub time_usec: u64,
6767 #[doc = "Latitude (WGS84)"]
6768 pub lat: i32,
6769 #[doc = "Longitude (WGS84)"]
6770 pub lon: i32,
6771 #[doc = "Altitude (MSL). Positive for up."]
6772 pub alt: i32,
6773 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
6774 pub eph: u16,
6775 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
6776 pub epv: u16,
6777 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
6778 pub vel: u16,
6779 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
6780 pub vn: i16,
6781 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
6782 pub ve: i16,
6783 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
6784 pub vd: i16,
6785 #[doc = "Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
6786 pub cog: u16,
6787 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix."]
6788 pub fix_type: u8,
6789 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
6790 pub satellites_visible: u8,
6791 #[doc = "GPS ID (zero indexed). Used for multiple GPS inputs"]
6792 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6793 pub id: u8,
6794 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
6795 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
6796 pub yaw: u16,
6797}
6798impl HIL_GPS_DATA {
6799 pub const ENCODED_LEN: usize = 39usize;
6800 pub const DEFAULT: Self = Self {
6801 time_usec: 0_u64,
6802 lat: 0_i32,
6803 lon: 0_i32,
6804 alt: 0_i32,
6805 eph: 0_u16,
6806 epv: 0_u16,
6807 vel: 0_u16,
6808 vn: 0_i16,
6809 ve: 0_i16,
6810 vd: 0_i16,
6811 cog: 0_u16,
6812 fix_type: 0_u8,
6813 satellites_visible: 0_u8,
6814 id: 0_u8,
6815 yaw: 0_u16,
6816 };
6817 #[cfg(feature = "arbitrary")]
6818 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6819 use arbitrary::{Arbitrary, Unstructured};
6820 let mut buf = [0u8; 1024];
6821 rng.fill_bytes(&mut buf);
6822 let mut unstructured = Unstructured::new(&buf);
6823 Self::arbitrary(&mut unstructured).unwrap_or_default()
6824 }
6825}
6826impl Default for HIL_GPS_DATA {
6827 fn default() -> Self {
6828 Self::DEFAULT.clone()
6829 }
6830}
6831impl MessageData for HIL_GPS_DATA {
6832 type Message = MavMessage;
6833 const ID: u32 = 113u32;
6834 const NAME: &'static str = "HIL_GPS";
6835 const EXTRA_CRC: u8 = 124u8;
6836 const ENCODED_LEN: usize = 39usize;
6837 fn deser(
6838 _version: MavlinkVersion,
6839 __input: &[u8],
6840 ) -> Result<Self, ::mavlink_core::error::ParserError> {
6841 let avail_len = __input.len();
6842 let mut payload_buf = [0; Self::ENCODED_LEN];
6843 let mut buf = if avail_len < Self::ENCODED_LEN {
6844 payload_buf[0..avail_len].copy_from_slice(__input);
6845 Bytes::new(&payload_buf)
6846 } else {
6847 Bytes::new(__input)
6848 };
6849 let mut __struct = Self::default();
6850 __struct.time_usec = buf.get_u64_le();
6851 __struct.lat = buf.get_i32_le();
6852 __struct.lon = buf.get_i32_le();
6853 __struct.alt = buf.get_i32_le();
6854 __struct.eph = buf.get_u16_le();
6855 __struct.epv = buf.get_u16_le();
6856 __struct.vel = buf.get_u16_le();
6857 __struct.vn = buf.get_i16_le();
6858 __struct.ve = buf.get_i16_le();
6859 __struct.vd = buf.get_i16_le();
6860 __struct.cog = buf.get_u16_le();
6861 __struct.fix_type = buf.get_u8();
6862 __struct.satellites_visible = buf.get_u8();
6863 __struct.id = buf.get_u8();
6864 __struct.yaw = buf.get_u16_le();
6865 Ok(__struct)
6866 }
6867 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
6868 let mut __tmp = BytesMut::new(bytes);
6869 #[allow(clippy::absurd_extreme_comparisons)]
6870 #[allow(unused_comparisons)]
6871 if __tmp.remaining() < Self::ENCODED_LEN {
6872 panic!(
6873 "buffer is too small (need {} bytes, but got {})",
6874 Self::ENCODED_LEN,
6875 __tmp.remaining(),
6876 )
6877 }
6878 __tmp.put_u64_le(self.time_usec);
6879 __tmp.put_i32_le(self.lat);
6880 __tmp.put_i32_le(self.lon);
6881 __tmp.put_i32_le(self.alt);
6882 __tmp.put_u16_le(self.eph);
6883 __tmp.put_u16_le(self.epv);
6884 __tmp.put_u16_le(self.vel);
6885 __tmp.put_i16_le(self.vn);
6886 __tmp.put_i16_le(self.ve);
6887 __tmp.put_i16_le(self.vd);
6888 __tmp.put_u16_le(self.cog);
6889 __tmp.put_u8(self.fix_type);
6890 __tmp.put_u8(self.satellites_visible);
6891 __tmp.put_u8(self.id);
6892 __tmp.put_u16_le(self.yaw);
6893 if matches!(version, MavlinkVersion::V2) {
6894 let len = __tmp.len();
6895 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
6896 } else {
6897 __tmp.len()
6898 }
6899 }
6900}
6901#[doc = "id: 234"]
6902#[doc = "Message appropriate for high latency connections like Iridium."]
6903#[derive(Debug, Clone, PartialEq)]
6904#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
6905#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
6906pub struct HIGH_LATENCY_DATA {
6907 #[doc = "A bitfield for use for autopilot-specific flags."]
6908 pub custom_mode: u32,
6909 #[doc = "Latitude"]
6910 pub latitude: i32,
6911 #[doc = "Longitude"]
6912 pub longitude: i32,
6913 #[doc = "roll"]
6914 pub roll: i16,
6915 #[doc = "pitch"]
6916 pub pitch: i16,
6917 #[doc = "heading"]
6918 pub heading: u16,
6919 #[doc = "heading setpoint"]
6920 pub heading_sp: i16,
6921 #[doc = "Altitude above mean sea level"]
6922 pub altitude_amsl: i16,
6923 #[doc = "Altitude setpoint relative to the home position"]
6924 pub altitude_sp: i16,
6925 #[doc = "distance to target"]
6926 pub wp_distance: u16,
6927 #[doc = "Bitmap of enabled system modes."]
6928 pub base_mode: MavModeFlag,
6929 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
6930 pub landed_state: MavLandedState,
6931 #[doc = "throttle (percentage)"]
6932 pub throttle: i8,
6933 #[doc = "airspeed"]
6934 pub airspeed: u8,
6935 #[doc = "airspeed setpoint"]
6936 pub airspeed_sp: u8,
6937 #[doc = "groundspeed"]
6938 pub groundspeed: u8,
6939 #[doc = "climb rate"]
6940 pub climb_rate: i8,
6941 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
6942 pub gps_nsat: u8,
6943 #[doc = "GPS Fix type."]
6944 pub gps_fix_type: GpsFixType,
6945 #[doc = "Remaining battery (percentage)"]
6946 pub battery_remaining: u8,
6947 #[doc = "Autopilot temperature (degrees C)"]
6948 pub temperature: i8,
6949 #[doc = "Air temperature (degrees C) from airspeed sensor"]
6950 pub temperature_air: i8,
6951 #[doc = "failsafe (each bit represents a failsafe where 0=ok, 1=failsafe active (bit0:RC, bit1:batt, bit2:GPS, bit3:GCS, bit4:fence)"]
6952 pub failsafe: u8,
6953 #[doc = "current waypoint number"]
6954 pub wp_num: u8,
6955}
6956impl HIGH_LATENCY_DATA {
6957 pub const ENCODED_LEN: usize = 40usize;
6958 pub const DEFAULT: Self = Self {
6959 custom_mode: 0_u32,
6960 latitude: 0_i32,
6961 longitude: 0_i32,
6962 roll: 0_i16,
6963 pitch: 0_i16,
6964 heading: 0_u16,
6965 heading_sp: 0_i16,
6966 altitude_amsl: 0_i16,
6967 altitude_sp: 0_i16,
6968 wp_distance: 0_u16,
6969 base_mode: MavModeFlag::DEFAULT,
6970 landed_state: MavLandedState::DEFAULT,
6971 throttle: 0_i8,
6972 airspeed: 0_u8,
6973 airspeed_sp: 0_u8,
6974 groundspeed: 0_u8,
6975 climb_rate: 0_i8,
6976 gps_nsat: 0_u8,
6977 gps_fix_type: GpsFixType::DEFAULT,
6978 battery_remaining: 0_u8,
6979 temperature: 0_i8,
6980 temperature_air: 0_i8,
6981 failsafe: 0_u8,
6982 wp_num: 0_u8,
6983 };
6984 #[cfg(feature = "arbitrary")]
6985 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
6986 use arbitrary::{Arbitrary, Unstructured};
6987 let mut buf = [0u8; 1024];
6988 rng.fill_bytes(&mut buf);
6989 let mut unstructured = Unstructured::new(&buf);
6990 Self::arbitrary(&mut unstructured).unwrap_or_default()
6991 }
6992}
6993impl Default for HIGH_LATENCY_DATA {
6994 fn default() -> Self {
6995 Self::DEFAULT.clone()
6996 }
6997}
6998impl MessageData for HIGH_LATENCY_DATA {
6999 type Message = MavMessage;
7000 const ID: u32 = 234u32;
7001 const NAME: &'static str = "HIGH_LATENCY";
7002 const EXTRA_CRC: u8 = 150u8;
7003 const ENCODED_LEN: usize = 40usize;
7004 fn deser(
7005 _version: MavlinkVersion,
7006 __input: &[u8],
7007 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7008 let avail_len = __input.len();
7009 let mut payload_buf = [0; Self::ENCODED_LEN];
7010 let mut buf = if avail_len < Self::ENCODED_LEN {
7011 payload_buf[0..avail_len].copy_from_slice(__input);
7012 Bytes::new(&payload_buf)
7013 } else {
7014 Bytes::new(__input)
7015 };
7016 let mut __struct = Self::default();
7017 __struct.custom_mode = buf.get_u32_le();
7018 __struct.latitude = buf.get_i32_le();
7019 __struct.longitude = buf.get_i32_le();
7020 __struct.roll = buf.get_i16_le();
7021 __struct.pitch = buf.get_i16_le();
7022 __struct.heading = buf.get_u16_le();
7023 __struct.heading_sp = buf.get_i16_le();
7024 __struct.altitude_amsl = buf.get_i16_le();
7025 __struct.altitude_sp = buf.get_i16_le();
7026 __struct.wp_distance = buf.get_u16_le();
7027 let tmp = buf.get_u8();
7028 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
7029 ::mavlink_core::error::ParserError::InvalidFlag {
7030 flag_type: "MavModeFlag",
7031 value: tmp as u32,
7032 },
7033 )?;
7034 let tmp = buf.get_u8();
7035 __struct.landed_state =
7036 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7037 enum_type: "MavLandedState",
7038 value: tmp as u32,
7039 })?;
7040 __struct.throttle = buf.get_i8();
7041 __struct.airspeed = buf.get_u8();
7042 __struct.airspeed_sp = buf.get_u8();
7043 __struct.groundspeed = buf.get_u8();
7044 __struct.climb_rate = buf.get_i8();
7045 __struct.gps_nsat = buf.get_u8();
7046 let tmp = buf.get_u8();
7047 __struct.gps_fix_type =
7048 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7049 enum_type: "GpsFixType",
7050 value: tmp as u32,
7051 })?;
7052 __struct.battery_remaining = buf.get_u8();
7053 __struct.temperature = buf.get_i8();
7054 __struct.temperature_air = buf.get_i8();
7055 __struct.failsafe = buf.get_u8();
7056 __struct.wp_num = buf.get_u8();
7057 Ok(__struct)
7058 }
7059 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7060 let mut __tmp = BytesMut::new(bytes);
7061 #[allow(clippy::absurd_extreme_comparisons)]
7062 #[allow(unused_comparisons)]
7063 if __tmp.remaining() < Self::ENCODED_LEN {
7064 panic!(
7065 "buffer is too small (need {} bytes, but got {})",
7066 Self::ENCODED_LEN,
7067 __tmp.remaining(),
7068 )
7069 }
7070 __tmp.put_u32_le(self.custom_mode);
7071 __tmp.put_i32_le(self.latitude);
7072 __tmp.put_i32_le(self.longitude);
7073 __tmp.put_i16_le(self.roll);
7074 __tmp.put_i16_le(self.pitch);
7075 __tmp.put_u16_le(self.heading);
7076 __tmp.put_i16_le(self.heading_sp);
7077 __tmp.put_i16_le(self.altitude_amsl);
7078 __tmp.put_i16_le(self.altitude_sp);
7079 __tmp.put_u16_le(self.wp_distance);
7080 __tmp.put_u8(self.base_mode.bits());
7081 __tmp.put_u8(self.landed_state as u8);
7082 __tmp.put_i8(self.throttle);
7083 __tmp.put_u8(self.airspeed);
7084 __tmp.put_u8(self.airspeed_sp);
7085 __tmp.put_u8(self.groundspeed);
7086 __tmp.put_i8(self.climb_rate);
7087 __tmp.put_u8(self.gps_nsat);
7088 __tmp.put_u8(self.gps_fix_type as u8);
7089 __tmp.put_u8(self.battery_remaining);
7090 __tmp.put_i8(self.temperature);
7091 __tmp.put_i8(self.temperature_air);
7092 __tmp.put_u8(self.failsafe);
7093 __tmp.put_u8(self.wp_num);
7094 if matches!(version, MavlinkVersion::V2) {
7095 let len = __tmp.len();
7096 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7097 } else {
7098 __tmp.len()
7099 }
7100 }
7101}
7102#[doc = "id: 12900"]
7103#[doc = "Data for filling the OpenDroneID Basic ID message. This and the below messages are primarily meant for feeding data to/from an OpenDroneID implementation. E.g. <https://github.com/opendroneid/opendroneid-core-c>. These messages are compatible with the ASTM F3411 Remote ID standard and the ASD-STAN prEN 4709-002 Direct Remote ID standard. Additional information and usage of these messages is documented at <https://mavlink.io/en/services/opendroneid.html>."]
7104#[derive(Debug, Clone, PartialEq)]
7105#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7106#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7107pub struct OPEN_DRONE_ID_BASIC_ID_DATA {
7108 #[doc = "System ID (0 for broadcast)."]
7109 pub target_system: u8,
7110 #[doc = "Component ID (0 for broadcast)."]
7111 pub target_component: u8,
7112 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
7113 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7114 pub id_or_mac: [u8; 20],
7115 #[doc = "Indicates the format for the uas_id field of this message."]
7116 pub id_type: MavOdidIdType,
7117 #[doc = "Indicates the type of UA (Unmanned Aircraft)."]
7118 pub ua_type: MavOdidUaType,
7119 #[doc = "UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field."]
7120 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7121 pub uas_id: [u8; 20],
7122}
7123impl OPEN_DRONE_ID_BASIC_ID_DATA {
7124 pub const ENCODED_LEN: usize = 44usize;
7125 pub const DEFAULT: Self = Self {
7126 target_system: 0_u8,
7127 target_component: 0_u8,
7128 id_or_mac: [0_u8; 20usize],
7129 id_type: MavOdidIdType::DEFAULT,
7130 ua_type: MavOdidUaType::DEFAULT,
7131 uas_id: [0_u8; 20usize],
7132 };
7133 #[cfg(feature = "arbitrary")]
7134 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7135 use arbitrary::{Arbitrary, Unstructured};
7136 let mut buf = [0u8; 1024];
7137 rng.fill_bytes(&mut buf);
7138 let mut unstructured = Unstructured::new(&buf);
7139 Self::arbitrary(&mut unstructured).unwrap_or_default()
7140 }
7141}
7142impl Default for OPEN_DRONE_ID_BASIC_ID_DATA {
7143 fn default() -> Self {
7144 Self::DEFAULT.clone()
7145 }
7146}
7147impl MessageData for OPEN_DRONE_ID_BASIC_ID_DATA {
7148 type Message = MavMessage;
7149 const ID: u32 = 12900u32;
7150 const NAME: &'static str = "OPEN_DRONE_ID_BASIC_ID";
7151 const EXTRA_CRC: u8 = 114u8;
7152 const ENCODED_LEN: usize = 44usize;
7153 fn deser(
7154 _version: MavlinkVersion,
7155 __input: &[u8],
7156 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7157 let avail_len = __input.len();
7158 let mut payload_buf = [0; Self::ENCODED_LEN];
7159 let mut buf = if avail_len < Self::ENCODED_LEN {
7160 payload_buf[0..avail_len].copy_from_slice(__input);
7161 Bytes::new(&payload_buf)
7162 } else {
7163 Bytes::new(__input)
7164 };
7165 let mut __struct = Self::default();
7166 __struct.target_system = buf.get_u8();
7167 __struct.target_component = buf.get_u8();
7168 for v in &mut __struct.id_or_mac {
7169 let val = buf.get_u8();
7170 *v = val;
7171 }
7172 let tmp = buf.get_u8();
7173 __struct.id_type =
7174 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7175 enum_type: "MavOdidIdType",
7176 value: tmp as u32,
7177 })?;
7178 let tmp = buf.get_u8();
7179 __struct.ua_type =
7180 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7181 enum_type: "MavOdidUaType",
7182 value: tmp as u32,
7183 })?;
7184 for v in &mut __struct.uas_id {
7185 let val = buf.get_u8();
7186 *v = val;
7187 }
7188 Ok(__struct)
7189 }
7190 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7191 let mut __tmp = BytesMut::new(bytes);
7192 #[allow(clippy::absurd_extreme_comparisons)]
7193 #[allow(unused_comparisons)]
7194 if __tmp.remaining() < Self::ENCODED_LEN {
7195 panic!(
7196 "buffer is too small (need {} bytes, but got {})",
7197 Self::ENCODED_LEN,
7198 __tmp.remaining(),
7199 )
7200 }
7201 __tmp.put_u8(self.target_system);
7202 __tmp.put_u8(self.target_component);
7203 for val in &self.id_or_mac {
7204 __tmp.put_u8(*val);
7205 }
7206 __tmp.put_u8(self.id_type as u8);
7207 __tmp.put_u8(self.ua_type as u8);
7208 for val in &self.uas_id {
7209 __tmp.put_u8(*val);
7210 }
7211 if matches!(version, MavlinkVersion::V2) {
7212 let len = __tmp.len();
7213 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7214 } else {
7215 __tmp.len()
7216 }
7217 }
7218}
7219#[doc = "id: 147"]
7220#[doc = "Battery information. Updates GCS with flight controller battery status. Smart batteries also use this message, but may additionally send BATTERY_INFO."]
7221#[derive(Debug, Clone, PartialEq)]
7222#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7223#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7224pub struct BATTERY_STATUS_DATA {
7225 #[doc = "Consumed charge, -1: autopilot does not provide consumption estimate"]
7226 pub current_consumed: i32,
7227 #[doc = "Consumed energy, -1: autopilot does not provide energy consumption estimate"]
7228 pub energy_consumed: i32,
7229 #[doc = "Temperature of the battery. INT16_MAX for unknown temperature."]
7230 pub temperature: i16,
7231 #[doc = "Battery voltage of cells 1 to 10 (see voltages_ext for cells 11-14). Cells in this field above the valid cell count for this battery should have the UINT16_MAX value. If individual cell voltages are unknown or not measured for this battery, then the overall battery voltage should be filled in cell 0, with all others set to UINT16_MAX. If the voltage of the battery is greater than (UINT16_MAX - 1), then cell 0 should be set to (UINT16_MAX - 1), and cell 1 to the remaining voltage. This can be extended to multiple cells if the total voltage is greater than 2 * (UINT16_MAX - 1)."]
7232 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7233 pub voltages: [u16; 10],
7234 #[doc = "Battery current, -1: autopilot does not measure the current"]
7235 pub current_battery: i16,
7236 #[doc = "Battery ID"]
7237 pub id: u8,
7238 #[doc = "Function of the battery"]
7239 pub battery_function: MavBatteryFunction,
7240 #[doc = "Type (chemistry) of the battery"]
7241 pub mavtype: MavBatteryType,
7242 #[doc = "Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery."]
7243 pub battery_remaining: i8,
7244 #[doc = "Remaining battery time, 0: autopilot does not provide remaining battery time estimate"]
7245 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7246 pub time_remaining: i32,
7247 #[doc = "State for extent of discharge, provided by autopilot for warning or external reactions"]
7248 #[cfg_attr(feature = "serde", serde(default))]
7249 pub charge_state: MavBatteryChargeState,
7250 #[doc = "Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead."]
7251 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7252 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7253 pub voltages_ext: [u16; 4],
7254 #[doc = "Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode."]
7255 #[cfg_attr(feature = "serde", serde(default))]
7256 pub mode: MavBatteryMode,
7257 #[doc = "Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported)."]
7258 #[cfg_attr(feature = "serde", serde(default))]
7259 pub fault_bitmask: MavBatteryFault,
7260}
7261impl BATTERY_STATUS_DATA {
7262 pub const ENCODED_LEN: usize = 54usize;
7263 pub const DEFAULT: Self = Self {
7264 current_consumed: 0_i32,
7265 energy_consumed: 0_i32,
7266 temperature: 0_i16,
7267 voltages: [0_u16; 10usize],
7268 current_battery: 0_i16,
7269 id: 0_u8,
7270 battery_function: MavBatteryFunction::DEFAULT,
7271 mavtype: MavBatteryType::DEFAULT,
7272 battery_remaining: 0_i8,
7273 time_remaining: 0_i32,
7274 charge_state: MavBatteryChargeState::DEFAULT,
7275 voltages_ext: [0_u16; 4usize],
7276 mode: MavBatteryMode::DEFAULT,
7277 fault_bitmask: MavBatteryFault::DEFAULT,
7278 };
7279 #[cfg(feature = "arbitrary")]
7280 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7281 use arbitrary::{Arbitrary, Unstructured};
7282 let mut buf = [0u8; 1024];
7283 rng.fill_bytes(&mut buf);
7284 let mut unstructured = Unstructured::new(&buf);
7285 Self::arbitrary(&mut unstructured).unwrap_or_default()
7286 }
7287}
7288impl Default for BATTERY_STATUS_DATA {
7289 fn default() -> Self {
7290 Self::DEFAULT.clone()
7291 }
7292}
7293impl MessageData for BATTERY_STATUS_DATA {
7294 type Message = MavMessage;
7295 const ID: u32 = 147u32;
7296 const NAME: &'static str = "BATTERY_STATUS";
7297 const EXTRA_CRC: u8 = 154u8;
7298 const ENCODED_LEN: usize = 54usize;
7299 fn deser(
7300 _version: MavlinkVersion,
7301 __input: &[u8],
7302 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7303 let avail_len = __input.len();
7304 let mut payload_buf = [0; Self::ENCODED_LEN];
7305 let mut buf = if avail_len < Self::ENCODED_LEN {
7306 payload_buf[0..avail_len].copy_from_slice(__input);
7307 Bytes::new(&payload_buf)
7308 } else {
7309 Bytes::new(__input)
7310 };
7311 let mut __struct = Self::default();
7312 __struct.current_consumed = buf.get_i32_le();
7313 __struct.energy_consumed = buf.get_i32_le();
7314 __struct.temperature = buf.get_i16_le();
7315 for v in &mut __struct.voltages {
7316 let val = buf.get_u16_le();
7317 *v = val;
7318 }
7319 __struct.current_battery = buf.get_i16_le();
7320 __struct.id = buf.get_u8();
7321 let tmp = buf.get_u8();
7322 __struct.battery_function =
7323 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7324 enum_type: "MavBatteryFunction",
7325 value: tmp as u32,
7326 })?;
7327 let tmp = buf.get_u8();
7328 __struct.mavtype =
7329 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7330 enum_type: "MavBatteryType",
7331 value: tmp as u32,
7332 })?;
7333 __struct.battery_remaining = buf.get_i8();
7334 __struct.time_remaining = buf.get_i32_le();
7335 let tmp = buf.get_u8();
7336 __struct.charge_state =
7337 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7338 enum_type: "MavBatteryChargeState",
7339 value: tmp as u32,
7340 })?;
7341 for v in &mut __struct.voltages_ext {
7342 let val = buf.get_u16_le();
7343 *v = val;
7344 }
7345 let tmp = buf.get_u8();
7346 __struct.mode =
7347 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
7348 enum_type: "MavBatteryMode",
7349 value: tmp as u32,
7350 })?;
7351 let tmp = buf.get_u32_le();
7352 __struct.fault_bitmask = MavBatteryFault::from_bits(tmp & MavBatteryFault::all().bits())
7353 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
7354 flag_type: "MavBatteryFault",
7355 value: tmp as u32,
7356 })?;
7357 Ok(__struct)
7358 }
7359 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7360 let mut __tmp = BytesMut::new(bytes);
7361 #[allow(clippy::absurd_extreme_comparisons)]
7362 #[allow(unused_comparisons)]
7363 if __tmp.remaining() < Self::ENCODED_LEN {
7364 panic!(
7365 "buffer is too small (need {} bytes, but got {})",
7366 Self::ENCODED_LEN,
7367 __tmp.remaining(),
7368 )
7369 }
7370 __tmp.put_i32_le(self.current_consumed);
7371 __tmp.put_i32_le(self.energy_consumed);
7372 __tmp.put_i16_le(self.temperature);
7373 for val in &self.voltages {
7374 __tmp.put_u16_le(*val);
7375 }
7376 __tmp.put_i16_le(self.current_battery);
7377 __tmp.put_u8(self.id);
7378 __tmp.put_u8(self.battery_function as u8);
7379 __tmp.put_u8(self.mavtype as u8);
7380 __tmp.put_i8(self.battery_remaining);
7381 __tmp.put_i32_le(self.time_remaining);
7382 __tmp.put_u8(self.charge_state as u8);
7383 for val in &self.voltages_ext {
7384 __tmp.put_u16_le(*val);
7385 }
7386 __tmp.put_u8(self.mode as u8);
7387 __tmp.put_u32_le(self.fault_bitmask.bits());
7388 if matches!(version, MavlinkVersion::V2) {
7389 let len = __tmp.len();
7390 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7391 } else {
7392 __tmp.len()
7393 }
7394 }
7395}
7396#[doc = "id: 225"]
7397#[doc = "EFI status output."]
7398#[derive(Debug, Clone, PartialEq)]
7399#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7400#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7401pub struct EFI_STATUS_DATA {
7402 #[doc = "ECU index"]
7403 pub ecu_index: f32,
7404 #[doc = "RPM"]
7405 pub rpm: f32,
7406 #[doc = "Fuel consumed"]
7407 pub fuel_consumed: f32,
7408 #[doc = "Fuel flow rate"]
7409 pub fuel_flow: f32,
7410 #[doc = "Engine load"]
7411 pub engine_load: f32,
7412 #[doc = "Throttle position"]
7413 pub throttle_position: f32,
7414 #[doc = "Spark dwell time"]
7415 pub spark_dwell_time: f32,
7416 #[doc = "Barometric pressure"]
7417 pub barometric_pressure: f32,
7418 #[doc = "Intake manifold pressure("]
7419 pub intake_manifold_pressure: f32,
7420 #[doc = "Intake manifold temperature"]
7421 pub intake_manifold_temperature: f32,
7422 #[doc = "Cylinder head temperature"]
7423 pub cylinder_head_temperature: f32,
7424 #[doc = "Ignition timing (Crank angle degrees)"]
7425 pub ignition_timing: f32,
7426 #[doc = "Injection time"]
7427 pub injection_time: f32,
7428 #[doc = "Exhaust gas temperature"]
7429 pub exhaust_gas_temperature: f32,
7430 #[doc = "Output throttle"]
7431 pub throttle_out: f32,
7432 #[doc = "Pressure/temperature compensation"]
7433 pub pt_compensation: f32,
7434 #[doc = "EFI health status"]
7435 pub health: u8,
7436 #[doc = "Supply voltage to EFI sparking system. Zero in this value means \"unknown\", so if the supply voltage really is zero volts use 0.0001 instead."]
7437 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7438 pub ignition_voltage: f32,
7439 #[doc = "Fuel pressure. Zero in this value means \"unknown\", so if the fuel pressure really is zero kPa use 0.0001 instead."]
7440 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7441 pub fuel_pressure: f32,
7442}
7443impl EFI_STATUS_DATA {
7444 pub const ENCODED_LEN: usize = 73usize;
7445 pub const DEFAULT: Self = Self {
7446 ecu_index: 0.0_f32,
7447 rpm: 0.0_f32,
7448 fuel_consumed: 0.0_f32,
7449 fuel_flow: 0.0_f32,
7450 engine_load: 0.0_f32,
7451 throttle_position: 0.0_f32,
7452 spark_dwell_time: 0.0_f32,
7453 barometric_pressure: 0.0_f32,
7454 intake_manifold_pressure: 0.0_f32,
7455 intake_manifold_temperature: 0.0_f32,
7456 cylinder_head_temperature: 0.0_f32,
7457 ignition_timing: 0.0_f32,
7458 injection_time: 0.0_f32,
7459 exhaust_gas_temperature: 0.0_f32,
7460 throttle_out: 0.0_f32,
7461 pt_compensation: 0.0_f32,
7462 health: 0_u8,
7463 ignition_voltage: 0.0_f32,
7464 fuel_pressure: 0.0_f32,
7465 };
7466 #[cfg(feature = "arbitrary")]
7467 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7468 use arbitrary::{Arbitrary, Unstructured};
7469 let mut buf = [0u8; 1024];
7470 rng.fill_bytes(&mut buf);
7471 let mut unstructured = Unstructured::new(&buf);
7472 Self::arbitrary(&mut unstructured).unwrap_or_default()
7473 }
7474}
7475impl Default for EFI_STATUS_DATA {
7476 fn default() -> Self {
7477 Self::DEFAULT.clone()
7478 }
7479}
7480impl MessageData for EFI_STATUS_DATA {
7481 type Message = MavMessage;
7482 const ID: u32 = 225u32;
7483 const NAME: &'static str = "EFI_STATUS";
7484 const EXTRA_CRC: u8 = 208u8;
7485 const ENCODED_LEN: usize = 73usize;
7486 fn deser(
7487 _version: MavlinkVersion,
7488 __input: &[u8],
7489 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7490 let avail_len = __input.len();
7491 let mut payload_buf = [0; Self::ENCODED_LEN];
7492 let mut buf = if avail_len < Self::ENCODED_LEN {
7493 payload_buf[0..avail_len].copy_from_slice(__input);
7494 Bytes::new(&payload_buf)
7495 } else {
7496 Bytes::new(__input)
7497 };
7498 let mut __struct = Self::default();
7499 __struct.ecu_index = buf.get_f32_le();
7500 __struct.rpm = buf.get_f32_le();
7501 __struct.fuel_consumed = buf.get_f32_le();
7502 __struct.fuel_flow = buf.get_f32_le();
7503 __struct.engine_load = buf.get_f32_le();
7504 __struct.throttle_position = buf.get_f32_le();
7505 __struct.spark_dwell_time = buf.get_f32_le();
7506 __struct.barometric_pressure = buf.get_f32_le();
7507 __struct.intake_manifold_pressure = buf.get_f32_le();
7508 __struct.intake_manifold_temperature = buf.get_f32_le();
7509 __struct.cylinder_head_temperature = buf.get_f32_le();
7510 __struct.ignition_timing = buf.get_f32_le();
7511 __struct.injection_time = buf.get_f32_le();
7512 __struct.exhaust_gas_temperature = buf.get_f32_le();
7513 __struct.throttle_out = buf.get_f32_le();
7514 __struct.pt_compensation = buf.get_f32_le();
7515 __struct.health = buf.get_u8();
7516 __struct.ignition_voltage = buf.get_f32_le();
7517 __struct.fuel_pressure = buf.get_f32_le();
7518 Ok(__struct)
7519 }
7520 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7521 let mut __tmp = BytesMut::new(bytes);
7522 #[allow(clippy::absurd_extreme_comparisons)]
7523 #[allow(unused_comparisons)]
7524 if __tmp.remaining() < Self::ENCODED_LEN {
7525 panic!(
7526 "buffer is too small (need {} bytes, but got {})",
7527 Self::ENCODED_LEN,
7528 __tmp.remaining(),
7529 )
7530 }
7531 __tmp.put_f32_le(self.ecu_index);
7532 __tmp.put_f32_le(self.rpm);
7533 __tmp.put_f32_le(self.fuel_consumed);
7534 __tmp.put_f32_le(self.fuel_flow);
7535 __tmp.put_f32_le(self.engine_load);
7536 __tmp.put_f32_le(self.throttle_position);
7537 __tmp.put_f32_le(self.spark_dwell_time);
7538 __tmp.put_f32_le(self.barometric_pressure);
7539 __tmp.put_f32_le(self.intake_manifold_pressure);
7540 __tmp.put_f32_le(self.intake_manifold_temperature);
7541 __tmp.put_f32_le(self.cylinder_head_temperature);
7542 __tmp.put_f32_le(self.ignition_timing);
7543 __tmp.put_f32_le(self.injection_time);
7544 __tmp.put_f32_le(self.exhaust_gas_temperature);
7545 __tmp.put_f32_le(self.throttle_out);
7546 __tmp.put_f32_le(self.pt_compensation);
7547 __tmp.put_u8(self.health);
7548 __tmp.put_f32_le(self.ignition_voltage);
7549 __tmp.put_f32_le(self.fuel_pressure);
7550 if matches!(version, MavlinkVersion::V2) {
7551 let len = __tmp.len();
7552 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7553 } else {
7554 __tmp.len()
7555 }
7556 }
7557}
7558#[doc = "id: 9005"]
7559#[doc = "Winch status."]
7560#[derive(Debug, Clone, PartialEq)]
7561#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7562#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7563pub struct WINCH_STATUS_DATA {
7564 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
7565 pub time_usec: u64,
7566 #[doc = "Length of line released. NaN if unknown"]
7567 pub line_length: f32,
7568 #[doc = "Speed line is being released or retracted. Positive values if being released, negative values if being retracted, NaN if unknown"]
7569 pub speed: f32,
7570 #[doc = "Tension on the line. NaN if unknown"]
7571 pub tension: f32,
7572 #[doc = "Voltage of the battery supplying the winch. NaN if unknown"]
7573 pub voltage: f32,
7574 #[doc = "Current draw from the winch. NaN if unknown"]
7575 pub current: f32,
7576 #[doc = "Status flags"]
7577 pub status: MavWinchStatusFlag,
7578 #[doc = "Temperature of the motor. INT16_MAX if unknown"]
7579 pub temperature: i16,
7580}
7581impl WINCH_STATUS_DATA {
7582 pub const ENCODED_LEN: usize = 34usize;
7583 pub const DEFAULT: Self = Self {
7584 time_usec: 0_u64,
7585 line_length: 0.0_f32,
7586 speed: 0.0_f32,
7587 tension: 0.0_f32,
7588 voltage: 0.0_f32,
7589 current: 0.0_f32,
7590 status: MavWinchStatusFlag::DEFAULT,
7591 temperature: 0_i16,
7592 };
7593 #[cfg(feature = "arbitrary")]
7594 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7595 use arbitrary::{Arbitrary, Unstructured};
7596 let mut buf = [0u8; 1024];
7597 rng.fill_bytes(&mut buf);
7598 let mut unstructured = Unstructured::new(&buf);
7599 Self::arbitrary(&mut unstructured).unwrap_or_default()
7600 }
7601}
7602impl Default for WINCH_STATUS_DATA {
7603 fn default() -> Self {
7604 Self::DEFAULT.clone()
7605 }
7606}
7607impl MessageData for WINCH_STATUS_DATA {
7608 type Message = MavMessage;
7609 const ID: u32 = 9005u32;
7610 const NAME: &'static str = "WINCH_STATUS";
7611 const EXTRA_CRC: u8 = 117u8;
7612 const ENCODED_LEN: usize = 34usize;
7613 fn deser(
7614 _version: MavlinkVersion,
7615 __input: &[u8],
7616 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7617 let avail_len = __input.len();
7618 let mut payload_buf = [0; Self::ENCODED_LEN];
7619 let mut buf = if avail_len < Self::ENCODED_LEN {
7620 payload_buf[0..avail_len].copy_from_slice(__input);
7621 Bytes::new(&payload_buf)
7622 } else {
7623 Bytes::new(__input)
7624 };
7625 let mut __struct = Self::default();
7626 __struct.time_usec = buf.get_u64_le();
7627 __struct.line_length = buf.get_f32_le();
7628 __struct.speed = buf.get_f32_le();
7629 __struct.tension = buf.get_f32_le();
7630 __struct.voltage = buf.get_f32_le();
7631 __struct.current = buf.get_f32_le();
7632 let tmp = buf.get_u32_le();
7633 __struct.status = MavWinchStatusFlag::from_bits(tmp & MavWinchStatusFlag::all().bits())
7634 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
7635 flag_type: "MavWinchStatusFlag",
7636 value: tmp as u32,
7637 })?;
7638 __struct.temperature = buf.get_i16_le();
7639 Ok(__struct)
7640 }
7641 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7642 let mut __tmp = BytesMut::new(bytes);
7643 #[allow(clippy::absurd_extreme_comparisons)]
7644 #[allow(unused_comparisons)]
7645 if __tmp.remaining() < Self::ENCODED_LEN {
7646 panic!(
7647 "buffer is too small (need {} bytes, but got {})",
7648 Self::ENCODED_LEN,
7649 __tmp.remaining(),
7650 )
7651 }
7652 __tmp.put_u64_le(self.time_usec);
7653 __tmp.put_f32_le(self.line_length);
7654 __tmp.put_f32_le(self.speed);
7655 __tmp.put_f32_le(self.tension);
7656 __tmp.put_f32_le(self.voltage);
7657 __tmp.put_f32_le(self.current);
7658 __tmp.put_u32_le(self.status.bits());
7659 __tmp.put_i16_le(self.temperature);
7660 if matches!(version, MavlinkVersion::V2) {
7661 let len = __tmp.len();
7662 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7663 } else {
7664 __tmp.len()
7665 }
7666 }
7667}
7668#[doc = "id: 10005"]
7669#[doc = "Flight Identification for ADSB-Out vehicles."]
7670#[derive(Debug, Clone, PartialEq)]
7671#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7672#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7673pub struct UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
7674 #[doc = "Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable. Reflects Control message setting. This is null-terminated."]
7675 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7676 pub flight_id: [u8; 9],
7677}
7678impl UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
7679 pub const ENCODED_LEN: usize = 9usize;
7680 pub const DEFAULT: Self = Self {
7681 flight_id: [0_u8; 9usize],
7682 };
7683 #[cfg(feature = "arbitrary")]
7684 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7685 use arbitrary::{Arbitrary, Unstructured};
7686 let mut buf = [0u8; 1024];
7687 rng.fill_bytes(&mut buf);
7688 let mut unstructured = Unstructured::new(&buf);
7689 Self::arbitrary(&mut unstructured).unwrap_or_default()
7690 }
7691}
7692impl Default for UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
7693 fn default() -> Self {
7694 Self::DEFAULT.clone()
7695 }
7696}
7697impl MessageData for UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA {
7698 type Message = MavMessage;
7699 const ID: u32 = 10005u32;
7700 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG_FLIGHTID";
7701 const EXTRA_CRC: u8 = 103u8;
7702 const ENCODED_LEN: usize = 9usize;
7703 fn deser(
7704 _version: MavlinkVersion,
7705 __input: &[u8],
7706 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7707 let avail_len = __input.len();
7708 let mut payload_buf = [0; Self::ENCODED_LEN];
7709 let mut buf = if avail_len < Self::ENCODED_LEN {
7710 payload_buf[0..avail_len].copy_from_slice(__input);
7711 Bytes::new(&payload_buf)
7712 } else {
7713 Bytes::new(__input)
7714 };
7715 let mut __struct = Self::default();
7716 for v in &mut __struct.flight_id {
7717 let val = buf.get_u8();
7718 *v = val;
7719 }
7720 Ok(__struct)
7721 }
7722 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7723 let mut __tmp = BytesMut::new(bytes);
7724 #[allow(clippy::absurd_extreme_comparisons)]
7725 #[allow(unused_comparisons)]
7726 if __tmp.remaining() < Self::ENCODED_LEN {
7727 panic!(
7728 "buffer is too small (need {} bytes, but got {})",
7729 Self::ENCODED_LEN,
7730 __tmp.remaining(),
7731 )
7732 }
7733 for val in &self.flight_id {
7734 __tmp.put_u8(*val);
7735 }
7736 if matches!(version, MavlinkVersion::V2) {
7737 let len = __tmp.len();
7738 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7739 } else {
7740 __tmp.len()
7741 }
7742 }
7743}
7744#[doc = "id: 4"]
7745#[doc = "A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections. The ping microservice is documented at <https://mavlink.io/en/services/ping.html>."]
7746#[derive(Debug, Clone, PartialEq)]
7747#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7748#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7749pub struct PING_DATA {
7750 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7751 pub time_usec: u64,
7752 #[doc = "PING sequence"]
7753 pub seq: u32,
7754 #[doc = "0: request ping from all receiving systems. If greater than 0: message is a ping response and number is the system id of the requesting system"]
7755 pub target_system: u8,
7756 #[doc = "0: request ping from all receiving components. If greater than 0: message is a ping response and number is the component id of the requesting component."]
7757 pub target_component: u8,
7758}
7759impl PING_DATA {
7760 pub const ENCODED_LEN: usize = 14usize;
7761 pub const DEFAULT: Self = Self {
7762 time_usec: 0_u64,
7763 seq: 0_u32,
7764 target_system: 0_u8,
7765 target_component: 0_u8,
7766 };
7767 #[cfg(feature = "arbitrary")]
7768 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7769 use arbitrary::{Arbitrary, Unstructured};
7770 let mut buf = [0u8; 1024];
7771 rng.fill_bytes(&mut buf);
7772 let mut unstructured = Unstructured::new(&buf);
7773 Self::arbitrary(&mut unstructured).unwrap_or_default()
7774 }
7775}
7776impl Default for PING_DATA {
7777 fn default() -> Self {
7778 Self::DEFAULT.clone()
7779 }
7780}
7781impl MessageData for PING_DATA {
7782 type Message = MavMessage;
7783 const ID: u32 = 4u32;
7784 const NAME: &'static str = "PING";
7785 const EXTRA_CRC: u8 = 237u8;
7786 const ENCODED_LEN: usize = 14usize;
7787 fn deser(
7788 _version: MavlinkVersion,
7789 __input: &[u8],
7790 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7791 let avail_len = __input.len();
7792 let mut payload_buf = [0; Self::ENCODED_LEN];
7793 let mut buf = if avail_len < Self::ENCODED_LEN {
7794 payload_buf[0..avail_len].copy_from_slice(__input);
7795 Bytes::new(&payload_buf)
7796 } else {
7797 Bytes::new(__input)
7798 };
7799 let mut __struct = Self::default();
7800 __struct.time_usec = buf.get_u64_le();
7801 __struct.seq = buf.get_u32_le();
7802 __struct.target_system = buf.get_u8();
7803 __struct.target_component = buf.get_u8();
7804 Ok(__struct)
7805 }
7806 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7807 let mut __tmp = BytesMut::new(bytes);
7808 #[allow(clippy::absurd_extreme_comparisons)]
7809 #[allow(unused_comparisons)]
7810 if __tmp.remaining() < Self::ENCODED_LEN {
7811 panic!(
7812 "buffer is too small (need {} bytes, but got {})",
7813 Self::ENCODED_LEN,
7814 __tmp.remaining(),
7815 )
7816 }
7817 __tmp.put_u64_le(self.time_usec);
7818 __tmp.put_u32_le(self.seq);
7819 __tmp.put_u8(self.target_system);
7820 __tmp.put_u8(self.target_component);
7821 if matches!(version, MavlinkVersion::V2) {
7822 let len = __tmp.len();
7823 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7824 } else {
7825 __tmp.len()
7826 }
7827 }
7828}
7829#[doc = "id: 114"]
7830#[doc = "Simulated optical flow from a flow sensor (e.g. PX4FLOW or optical mouse sensor)."]
7831#[derive(Debug, Clone, PartialEq)]
7832#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7833#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7834pub struct HIL_OPTICAL_FLOW_DATA {
7835 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
7836 pub time_usec: u64,
7837 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
7838 pub integration_time_us: u32,
7839 #[doc = "Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
7840 pub integrated_x: f32,
7841 #[doc = "Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
7842 pub integrated_y: f32,
7843 #[doc = "RH rotation around X axis"]
7844 pub integrated_xgyro: f32,
7845 #[doc = "RH rotation around Y axis"]
7846 pub integrated_ygyro: f32,
7847 #[doc = "RH rotation around Z axis"]
7848 pub integrated_zgyro: f32,
7849 #[doc = "Time since the distance was sampled."]
7850 pub time_delta_distance_us: u32,
7851 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
7852 pub distance: f32,
7853 #[doc = "Temperature"]
7854 pub temperature: i16,
7855 #[doc = "Sensor ID"]
7856 pub sensor_id: u8,
7857 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
7858 pub quality: u8,
7859}
7860impl HIL_OPTICAL_FLOW_DATA {
7861 pub const ENCODED_LEN: usize = 44usize;
7862 pub const DEFAULT: Self = Self {
7863 time_usec: 0_u64,
7864 integration_time_us: 0_u32,
7865 integrated_x: 0.0_f32,
7866 integrated_y: 0.0_f32,
7867 integrated_xgyro: 0.0_f32,
7868 integrated_ygyro: 0.0_f32,
7869 integrated_zgyro: 0.0_f32,
7870 time_delta_distance_us: 0_u32,
7871 distance: 0.0_f32,
7872 temperature: 0_i16,
7873 sensor_id: 0_u8,
7874 quality: 0_u8,
7875 };
7876 #[cfg(feature = "arbitrary")]
7877 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
7878 use arbitrary::{Arbitrary, Unstructured};
7879 let mut buf = [0u8; 1024];
7880 rng.fill_bytes(&mut buf);
7881 let mut unstructured = Unstructured::new(&buf);
7882 Self::arbitrary(&mut unstructured).unwrap_or_default()
7883 }
7884}
7885impl Default for HIL_OPTICAL_FLOW_DATA {
7886 fn default() -> Self {
7887 Self::DEFAULT.clone()
7888 }
7889}
7890impl MessageData for HIL_OPTICAL_FLOW_DATA {
7891 type Message = MavMessage;
7892 const ID: u32 = 114u32;
7893 const NAME: &'static str = "HIL_OPTICAL_FLOW";
7894 const EXTRA_CRC: u8 = 237u8;
7895 const ENCODED_LEN: usize = 44usize;
7896 fn deser(
7897 _version: MavlinkVersion,
7898 __input: &[u8],
7899 ) -> Result<Self, ::mavlink_core::error::ParserError> {
7900 let avail_len = __input.len();
7901 let mut payload_buf = [0; Self::ENCODED_LEN];
7902 let mut buf = if avail_len < Self::ENCODED_LEN {
7903 payload_buf[0..avail_len].copy_from_slice(__input);
7904 Bytes::new(&payload_buf)
7905 } else {
7906 Bytes::new(__input)
7907 };
7908 let mut __struct = Self::default();
7909 __struct.time_usec = buf.get_u64_le();
7910 __struct.integration_time_us = buf.get_u32_le();
7911 __struct.integrated_x = buf.get_f32_le();
7912 __struct.integrated_y = buf.get_f32_le();
7913 __struct.integrated_xgyro = buf.get_f32_le();
7914 __struct.integrated_ygyro = buf.get_f32_le();
7915 __struct.integrated_zgyro = buf.get_f32_le();
7916 __struct.time_delta_distance_us = buf.get_u32_le();
7917 __struct.distance = buf.get_f32_le();
7918 __struct.temperature = buf.get_i16_le();
7919 __struct.sensor_id = buf.get_u8();
7920 __struct.quality = buf.get_u8();
7921 Ok(__struct)
7922 }
7923 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
7924 let mut __tmp = BytesMut::new(bytes);
7925 #[allow(clippy::absurd_extreme_comparisons)]
7926 #[allow(unused_comparisons)]
7927 if __tmp.remaining() < Self::ENCODED_LEN {
7928 panic!(
7929 "buffer is too small (need {} bytes, but got {})",
7930 Self::ENCODED_LEN,
7931 __tmp.remaining(),
7932 )
7933 }
7934 __tmp.put_u64_le(self.time_usec);
7935 __tmp.put_u32_le(self.integration_time_us);
7936 __tmp.put_f32_le(self.integrated_x);
7937 __tmp.put_f32_le(self.integrated_y);
7938 __tmp.put_f32_le(self.integrated_xgyro);
7939 __tmp.put_f32_le(self.integrated_ygyro);
7940 __tmp.put_f32_le(self.integrated_zgyro);
7941 __tmp.put_u32_le(self.time_delta_distance_us);
7942 __tmp.put_f32_le(self.distance);
7943 __tmp.put_i16_le(self.temperature);
7944 __tmp.put_u8(self.sensor_id);
7945 __tmp.put_u8(self.quality);
7946 if matches!(version, MavlinkVersion::V2) {
7947 let len = __tmp.len();
7948 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
7949 } else {
7950 __tmp.len()
7951 }
7952 }
7953}
7954#[doc = "id: 269"]
7955#[doc = "Information about video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE, where param2 indicates the video stream id: 0 for all streams, 1 for first, 2 for second, etc."]
7956#[derive(Debug, Clone, PartialEq)]
7957#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
7958#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
7959pub struct VIDEO_STREAM_INFORMATION_DATA {
7960 #[doc = "Frame rate."]
7961 pub framerate: f32,
7962 #[doc = "Bit rate."]
7963 pub bitrate: u32,
7964 #[doc = "Bitmap of stream status flags."]
7965 pub flags: VideoStreamStatusFlags,
7966 #[doc = "Horizontal resolution."]
7967 pub resolution_h: u16,
7968 #[doc = "Vertical resolution."]
7969 pub resolution_v: u16,
7970 #[doc = "Video image rotation clockwise."]
7971 pub rotation: u16,
7972 #[doc = "Horizontal Field of view."]
7973 pub hfov: u16,
7974 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
7975 pub stream_id: u8,
7976 #[doc = "Number of streams available."]
7977 pub count: u8,
7978 #[doc = "Type of stream."]
7979 pub mavtype: VideoStreamType,
7980 #[doc = "Stream name."]
7981 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7982 pub name: [u8; 32],
7983 #[doc = "Video stream URI (TCP or RTSP URI ground station should connect to) or port number (UDP port ground station should listen to)."]
7984 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
7985 pub uri: [u8; 160],
7986 #[doc = "Encoding of stream."]
7987 #[cfg_attr(feature = "serde", serde(default))]
7988 pub encoding: VideoStreamEncoding,
7989 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
7990 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
7991 pub camera_device_id: u8,
7992}
7993impl VIDEO_STREAM_INFORMATION_DATA {
7994 pub const ENCODED_LEN: usize = 215usize;
7995 pub const DEFAULT: Self = Self {
7996 framerate: 0.0_f32,
7997 bitrate: 0_u32,
7998 flags: VideoStreamStatusFlags::DEFAULT,
7999 resolution_h: 0_u16,
8000 resolution_v: 0_u16,
8001 rotation: 0_u16,
8002 hfov: 0_u16,
8003 stream_id: 0_u8,
8004 count: 0_u8,
8005 mavtype: VideoStreamType::DEFAULT,
8006 name: [0_u8; 32usize],
8007 uri: [0_u8; 160usize],
8008 encoding: VideoStreamEncoding::DEFAULT,
8009 camera_device_id: 0_u8,
8010 };
8011 #[cfg(feature = "arbitrary")]
8012 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8013 use arbitrary::{Arbitrary, Unstructured};
8014 let mut buf = [0u8; 1024];
8015 rng.fill_bytes(&mut buf);
8016 let mut unstructured = Unstructured::new(&buf);
8017 Self::arbitrary(&mut unstructured).unwrap_or_default()
8018 }
8019}
8020impl Default for VIDEO_STREAM_INFORMATION_DATA {
8021 fn default() -> Self {
8022 Self::DEFAULT.clone()
8023 }
8024}
8025impl MessageData for VIDEO_STREAM_INFORMATION_DATA {
8026 type Message = MavMessage;
8027 const ID: u32 = 269u32;
8028 const NAME: &'static str = "VIDEO_STREAM_INFORMATION";
8029 const EXTRA_CRC: u8 = 109u8;
8030 const ENCODED_LEN: usize = 215usize;
8031 fn deser(
8032 _version: MavlinkVersion,
8033 __input: &[u8],
8034 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8035 let avail_len = __input.len();
8036 let mut payload_buf = [0; Self::ENCODED_LEN];
8037 let mut buf = if avail_len < Self::ENCODED_LEN {
8038 payload_buf[0..avail_len].copy_from_slice(__input);
8039 Bytes::new(&payload_buf)
8040 } else {
8041 Bytes::new(__input)
8042 };
8043 let mut __struct = Self::default();
8044 __struct.framerate = buf.get_f32_le();
8045 __struct.bitrate = buf.get_u32_le();
8046 let tmp = buf.get_u16_le();
8047 __struct.flags = VideoStreamStatusFlags::from_bits(
8048 tmp & VideoStreamStatusFlags::all().bits(),
8049 )
8050 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8051 flag_type: "VideoStreamStatusFlags",
8052 value: tmp as u32,
8053 })?;
8054 __struct.resolution_h = buf.get_u16_le();
8055 __struct.resolution_v = buf.get_u16_le();
8056 __struct.rotation = buf.get_u16_le();
8057 __struct.hfov = buf.get_u16_le();
8058 __struct.stream_id = buf.get_u8();
8059 __struct.count = buf.get_u8();
8060 let tmp = buf.get_u8();
8061 __struct.mavtype =
8062 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8063 enum_type: "VideoStreamType",
8064 value: tmp as u32,
8065 })?;
8066 for v in &mut __struct.name {
8067 let val = buf.get_u8();
8068 *v = val;
8069 }
8070 for v in &mut __struct.uri {
8071 let val = buf.get_u8();
8072 *v = val;
8073 }
8074 let tmp = buf.get_u8();
8075 __struct.encoding =
8076 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8077 enum_type: "VideoStreamEncoding",
8078 value: tmp as u32,
8079 })?;
8080 __struct.camera_device_id = buf.get_u8();
8081 Ok(__struct)
8082 }
8083 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8084 let mut __tmp = BytesMut::new(bytes);
8085 #[allow(clippy::absurd_extreme_comparisons)]
8086 #[allow(unused_comparisons)]
8087 if __tmp.remaining() < Self::ENCODED_LEN {
8088 panic!(
8089 "buffer is too small (need {} bytes, but got {})",
8090 Self::ENCODED_LEN,
8091 __tmp.remaining(),
8092 )
8093 }
8094 __tmp.put_f32_le(self.framerate);
8095 __tmp.put_u32_le(self.bitrate);
8096 __tmp.put_u16_le(self.flags.bits());
8097 __tmp.put_u16_le(self.resolution_h);
8098 __tmp.put_u16_le(self.resolution_v);
8099 __tmp.put_u16_le(self.rotation);
8100 __tmp.put_u16_le(self.hfov);
8101 __tmp.put_u8(self.stream_id);
8102 __tmp.put_u8(self.count);
8103 __tmp.put_u8(self.mavtype as u8);
8104 for val in &self.name {
8105 __tmp.put_u8(*val);
8106 }
8107 for val in &self.uri {
8108 __tmp.put_u8(*val);
8109 }
8110 __tmp.put_u8(self.encoding as u8);
8111 __tmp.put_u8(self.camera_device_id);
8112 if matches!(version, MavlinkVersion::V2) {
8113 let len = __tmp.len();
8114 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8115 } else {
8116 __tmp.len()
8117 }
8118 }
8119}
8120#[doc = "id: 64"]
8121#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
8122#[derive(Debug, Clone, PartialEq)]
8123#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8124#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8125pub struct LOCAL_POSITION_NED_COV_DATA {
8126 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
8127 pub time_usec: u64,
8128 #[doc = "X Position"]
8129 pub x: f32,
8130 #[doc = "Y Position"]
8131 pub y: f32,
8132 #[doc = "Z Position"]
8133 pub z: f32,
8134 #[doc = "X Speed"]
8135 pub vx: f32,
8136 #[doc = "Y Speed"]
8137 pub vy: f32,
8138 #[doc = "Z Speed"]
8139 pub vz: f32,
8140 #[doc = "X Acceleration"]
8141 pub ax: f32,
8142 #[doc = "Y Acceleration"]
8143 pub ay: f32,
8144 #[doc = "Z Acceleration"]
8145 pub az: f32,
8146 #[doc = "Row-major representation of position, velocity and acceleration 9x9 cross-covariance matrix upper right triangle (states: x, y, z, vx, vy, vz, ax, ay, az; first nine entries are the first ROW, next eight entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
8147 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8148 pub covariance: [f32; 45],
8149 #[doc = "Class id of the estimator this estimate originated from."]
8150 pub estimator_type: MavEstimatorType,
8151}
8152impl LOCAL_POSITION_NED_COV_DATA {
8153 pub const ENCODED_LEN: usize = 225usize;
8154 pub const DEFAULT: Self = Self {
8155 time_usec: 0_u64,
8156 x: 0.0_f32,
8157 y: 0.0_f32,
8158 z: 0.0_f32,
8159 vx: 0.0_f32,
8160 vy: 0.0_f32,
8161 vz: 0.0_f32,
8162 ax: 0.0_f32,
8163 ay: 0.0_f32,
8164 az: 0.0_f32,
8165 covariance: [0.0_f32; 45usize],
8166 estimator_type: MavEstimatorType::DEFAULT,
8167 };
8168 #[cfg(feature = "arbitrary")]
8169 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8170 use arbitrary::{Arbitrary, Unstructured};
8171 let mut buf = [0u8; 1024];
8172 rng.fill_bytes(&mut buf);
8173 let mut unstructured = Unstructured::new(&buf);
8174 Self::arbitrary(&mut unstructured).unwrap_or_default()
8175 }
8176}
8177impl Default for LOCAL_POSITION_NED_COV_DATA {
8178 fn default() -> Self {
8179 Self::DEFAULT.clone()
8180 }
8181}
8182impl MessageData for LOCAL_POSITION_NED_COV_DATA {
8183 type Message = MavMessage;
8184 const ID: u32 = 64u32;
8185 const NAME: &'static str = "LOCAL_POSITION_NED_COV";
8186 const EXTRA_CRC: u8 = 191u8;
8187 const ENCODED_LEN: usize = 225usize;
8188 fn deser(
8189 _version: MavlinkVersion,
8190 __input: &[u8],
8191 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8192 let avail_len = __input.len();
8193 let mut payload_buf = [0; Self::ENCODED_LEN];
8194 let mut buf = if avail_len < Self::ENCODED_LEN {
8195 payload_buf[0..avail_len].copy_from_slice(__input);
8196 Bytes::new(&payload_buf)
8197 } else {
8198 Bytes::new(__input)
8199 };
8200 let mut __struct = Self::default();
8201 __struct.time_usec = buf.get_u64_le();
8202 __struct.x = buf.get_f32_le();
8203 __struct.y = buf.get_f32_le();
8204 __struct.z = buf.get_f32_le();
8205 __struct.vx = buf.get_f32_le();
8206 __struct.vy = buf.get_f32_le();
8207 __struct.vz = buf.get_f32_le();
8208 __struct.ax = buf.get_f32_le();
8209 __struct.ay = buf.get_f32_le();
8210 __struct.az = buf.get_f32_le();
8211 for v in &mut __struct.covariance {
8212 let val = buf.get_f32_le();
8213 *v = val;
8214 }
8215 let tmp = buf.get_u8();
8216 __struct.estimator_type =
8217 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8218 enum_type: "MavEstimatorType",
8219 value: tmp as u32,
8220 })?;
8221 Ok(__struct)
8222 }
8223 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8224 let mut __tmp = BytesMut::new(bytes);
8225 #[allow(clippy::absurd_extreme_comparisons)]
8226 #[allow(unused_comparisons)]
8227 if __tmp.remaining() < Self::ENCODED_LEN {
8228 panic!(
8229 "buffer is too small (need {} bytes, but got {})",
8230 Self::ENCODED_LEN,
8231 __tmp.remaining(),
8232 )
8233 }
8234 __tmp.put_u64_le(self.time_usec);
8235 __tmp.put_f32_le(self.x);
8236 __tmp.put_f32_le(self.y);
8237 __tmp.put_f32_le(self.z);
8238 __tmp.put_f32_le(self.vx);
8239 __tmp.put_f32_le(self.vy);
8240 __tmp.put_f32_le(self.vz);
8241 __tmp.put_f32_le(self.ax);
8242 __tmp.put_f32_le(self.ay);
8243 __tmp.put_f32_le(self.az);
8244 for val in &self.covariance {
8245 __tmp.put_f32_le(*val);
8246 }
8247 __tmp.put_u8(self.estimator_type as u8);
8248 if matches!(version, MavlinkVersion::V2) {
8249 let len = __tmp.len();
8250 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8251 } else {
8252 __tmp.len()
8253 }
8254 }
8255}
8256#[doc = "id: 7"]
8257#[doc = "Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety."]
8258#[derive(Debug, Clone, PartialEq)]
8259#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8260#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8261pub struct AUTH_KEY_DATA {
8262 #[doc = "key"]
8263 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8264 pub key: [u8; 32],
8265}
8266impl AUTH_KEY_DATA {
8267 pub const ENCODED_LEN: usize = 32usize;
8268 pub const DEFAULT: Self = Self {
8269 key: [0_u8; 32usize],
8270 };
8271 #[cfg(feature = "arbitrary")]
8272 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8273 use arbitrary::{Arbitrary, Unstructured};
8274 let mut buf = [0u8; 1024];
8275 rng.fill_bytes(&mut buf);
8276 let mut unstructured = Unstructured::new(&buf);
8277 Self::arbitrary(&mut unstructured).unwrap_or_default()
8278 }
8279}
8280impl Default for AUTH_KEY_DATA {
8281 fn default() -> Self {
8282 Self::DEFAULT.clone()
8283 }
8284}
8285impl MessageData for AUTH_KEY_DATA {
8286 type Message = MavMessage;
8287 const ID: u32 = 7u32;
8288 const NAME: &'static str = "AUTH_KEY";
8289 const EXTRA_CRC: u8 = 119u8;
8290 const ENCODED_LEN: usize = 32usize;
8291 fn deser(
8292 _version: MavlinkVersion,
8293 __input: &[u8],
8294 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8295 let avail_len = __input.len();
8296 let mut payload_buf = [0; Self::ENCODED_LEN];
8297 let mut buf = if avail_len < Self::ENCODED_LEN {
8298 payload_buf[0..avail_len].copy_from_slice(__input);
8299 Bytes::new(&payload_buf)
8300 } else {
8301 Bytes::new(__input)
8302 };
8303 let mut __struct = Self::default();
8304 for v in &mut __struct.key {
8305 let val = buf.get_u8();
8306 *v = val;
8307 }
8308 Ok(__struct)
8309 }
8310 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8311 let mut __tmp = BytesMut::new(bytes);
8312 #[allow(clippy::absurd_extreme_comparisons)]
8313 #[allow(unused_comparisons)]
8314 if __tmp.remaining() < Self::ENCODED_LEN {
8315 panic!(
8316 "buffer is too small (need {} bytes, but got {})",
8317 Self::ENCODED_LEN,
8318 __tmp.remaining(),
8319 )
8320 }
8321 for val in &self.key {
8322 __tmp.put_u8(*val);
8323 }
8324 if matches!(version, MavlinkVersion::V2) {
8325 let len = __tmp.len();
8326 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8327 } else {
8328 __tmp.len()
8329 }
8330 }
8331}
8332#[doc = "id: 93"]
8333#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_CONTROLS."]
8334#[derive(Debug, Clone, PartialEq)]
8335#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8336#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8337pub struct HIL_ACTUATOR_CONTROLS_DATA {
8338 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
8339 pub time_usec: u64,
8340 #[doc = "Flags bitmask."]
8341 pub flags: HilActuatorControlsFlags,
8342 #[doc = "Control outputs -1 .. 1. Channel assignment depends on the simulated hardware."]
8343 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8344 pub controls: [f32; 16],
8345 #[doc = "System mode. Includes arming state."]
8346 pub mode: MavModeFlag,
8347}
8348impl HIL_ACTUATOR_CONTROLS_DATA {
8349 pub const ENCODED_LEN: usize = 81usize;
8350 pub const DEFAULT: Self = Self {
8351 time_usec: 0_u64,
8352 flags: HilActuatorControlsFlags::DEFAULT,
8353 controls: [0.0_f32; 16usize],
8354 mode: MavModeFlag::DEFAULT,
8355 };
8356 #[cfg(feature = "arbitrary")]
8357 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8358 use arbitrary::{Arbitrary, Unstructured};
8359 let mut buf = [0u8; 1024];
8360 rng.fill_bytes(&mut buf);
8361 let mut unstructured = Unstructured::new(&buf);
8362 Self::arbitrary(&mut unstructured).unwrap_or_default()
8363 }
8364}
8365impl Default for HIL_ACTUATOR_CONTROLS_DATA {
8366 fn default() -> Self {
8367 Self::DEFAULT.clone()
8368 }
8369}
8370impl MessageData for HIL_ACTUATOR_CONTROLS_DATA {
8371 type Message = MavMessage;
8372 const ID: u32 = 93u32;
8373 const NAME: &'static str = "HIL_ACTUATOR_CONTROLS";
8374 const EXTRA_CRC: u8 = 47u8;
8375 const ENCODED_LEN: usize = 81usize;
8376 fn deser(
8377 _version: MavlinkVersion,
8378 __input: &[u8],
8379 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8380 let avail_len = __input.len();
8381 let mut payload_buf = [0; Self::ENCODED_LEN];
8382 let mut buf = if avail_len < Self::ENCODED_LEN {
8383 payload_buf[0..avail_len].copy_from_slice(__input);
8384 Bytes::new(&payload_buf)
8385 } else {
8386 Bytes::new(__input)
8387 };
8388 let mut __struct = Self::default();
8389 __struct.time_usec = buf.get_u64_le();
8390 let tmp = buf.get_u64_le();
8391 __struct.flags =
8392 HilActuatorControlsFlags::from_bits(tmp & HilActuatorControlsFlags::all().bits())
8393 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8394 flag_type: "HilActuatorControlsFlags",
8395 value: tmp as u32,
8396 })?;
8397 for v in &mut __struct.controls {
8398 let val = buf.get_f32_le();
8399 *v = val;
8400 }
8401 let tmp = buf.get_u8();
8402 __struct.mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
8403 ::mavlink_core::error::ParserError::InvalidFlag {
8404 flag_type: "MavModeFlag",
8405 value: tmp as u32,
8406 },
8407 )?;
8408 Ok(__struct)
8409 }
8410 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8411 let mut __tmp = BytesMut::new(bytes);
8412 #[allow(clippy::absurd_extreme_comparisons)]
8413 #[allow(unused_comparisons)]
8414 if __tmp.remaining() < Self::ENCODED_LEN {
8415 panic!(
8416 "buffer is too small (need {} bytes, but got {})",
8417 Self::ENCODED_LEN,
8418 __tmp.remaining(),
8419 )
8420 }
8421 __tmp.put_u64_le(self.time_usec);
8422 __tmp.put_u64_le(self.flags.bits());
8423 for val in &self.controls {
8424 __tmp.put_f32_le(*val);
8425 }
8426 __tmp.put_u8(self.mode.bits());
8427 if matches!(version, MavlinkVersion::V2) {
8428 let len = __tmp.len();
8429 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8430 } else {
8431 __tmp.len()
8432 }
8433 }
8434}
8435#[doc = "id: 247"]
8436#[doc = "Information about a potential collision."]
8437#[derive(Debug, Clone, PartialEq)]
8438#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8439#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8440pub struct COLLISION_DATA {
8441 #[doc = "Unique identifier, domain based on src field"]
8442 pub id: u32,
8443 #[doc = "Estimated time until collision occurs"]
8444 pub time_to_minimum_delta: f32,
8445 #[doc = "Closest vertical distance between vehicle and object"]
8446 pub altitude_minimum_delta: f32,
8447 #[doc = "Closest horizontal distance between vehicle and object"]
8448 pub horizontal_minimum_delta: f32,
8449 #[doc = "Collision data source"]
8450 pub src: MavCollisionSrc,
8451 #[doc = "Action that is being taken to avoid this collision"]
8452 pub action: MavCollisionAction,
8453 #[doc = "How concerned the aircraft is about this collision"]
8454 pub threat_level: MavCollisionThreatLevel,
8455}
8456impl COLLISION_DATA {
8457 pub const ENCODED_LEN: usize = 19usize;
8458 pub const DEFAULT: Self = Self {
8459 id: 0_u32,
8460 time_to_minimum_delta: 0.0_f32,
8461 altitude_minimum_delta: 0.0_f32,
8462 horizontal_minimum_delta: 0.0_f32,
8463 src: MavCollisionSrc::DEFAULT,
8464 action: MavCollisionAction::DEFAULT,
8465 threat_level: MavCollisionThreatLevel::DEFAULT,
8466 };
8467 #[cfg(feature = "arbitrary")]
8468 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8469 use arbitrary::{Arbitrary, Unstructured};
8470 let mut buf = [0u8; 1024];
8471 rng.fill_bytes(&mut buf);
8472 let mut unstructured = Unstructured::new(&buf);
8473 Self::arbitrary(&mut unstructured).unwrap_or_default()
8474 }
8475}
8476impl Default for COLLISION_DATA {
8477 fn default() -> Self {
8478 Self::DEFAULT.clone()
8479 }
8480}
8481impl MessageData for COLLISION_DATA {
8482 type Message = MavMessage;
8483 const ID: u32 = 247u32;
8484 const NAME: &'static str = "COLLISION";
8485 const EXTRA_CRC: u8 = 81u8;
8486 const ENCODED_LEN: usize = 19usize;
8487 fn deser(
8488 _version: MavlinkVersion,
8489 __input: &[u8],
8490 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8491 let avail_len = __input.len();
8492 let mut payload_buf = [0; Self::ENCODED_LEN];
8493 let mut buf = if avail_len < Self::ENCODED_LEN {
8494 payload_buf[0..avail_len].copy_from_slice(__input);
8495 Bytes::new(&payload_buf)
8496 } else {
8497 Bytes::new(__input)
8498 };
8499 let mut __struct = Self::default();
8500 __struct.id = buf.get_u32_le();
8501 __struct.time_to_minimum_delta = buf.get_f32_le();
8502 __struct.altitude_minimum_delta = buf.get_f32_le();
8503 __struct.horizontal_minimum_delta = buf.get_f32_le();
8504 let tmp = buf.get_u8();
8505 __struct.src =
8506 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8507 enum_type: "MavCollisionSrc",
8508 value: tmp as u32,
8509 })?;
8510 let tmp = buf.get_u8();
8511 __struct.action =
8512 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8513 enum_type: "MavCollisionAction",
8514 value: tmp as u32,
8515 })?;
8516 let tmp = buf.get_u8();
8517 __struct.threat_level =
8518 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8519 enum_type: "MavCollisionThreatLevel",
8520 value: tmp as u32,
8521 })?;
8522 Ok(__struct)
8523 }
8524 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8525 let mut __tmp = BytesMut::new(bytes);
8526 #[allow(clippy::absurd_extreme_comparisons)]
8527 #[allow(unused_comparisons)]
8528 if __tmp.remaining() < Self::ENCODED_LEN {
8529 panic!(
8530 "buffer is too small (need {} bytes, but got {})",
8531 Self::ENCODED_LEN,
8532 __tmp.remaining(),
8533 )
8534 }
8535 __tmp.put_u32_le(self.id);
8536 __tmp.put_f32_le(self.time_to_minimum_delta);
8537 __tmp.put_f32_le(self.altitude_minimum_delta);
8538 __tmp.put_f32_le(self.horizontal_minimum_delta);
8539 __tmp.put_u8(self.src as u8);
8540 __tmp.put_u8(self.action as u8);
8541 __tmp.put_u8(self.threat_level as u8);
8542 if matches!(version, MavlinkVersion::V2) {
8543 let len = __tmp.len();
8544 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8545 } else {
8546 __tmp.len()
8547 }
8548 }
8549}
8550#[doc = "id: 10004"]
8551#[doc = "Aircraft Registration."]
8552#[derive(Debug, Clone, PartialEq)]
8553#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8554#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8555pub struct UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
8556 #[doc = "Aircraft Registration (ASCII string A-Z, 0-9 only), e.g. \"N8644B \". Trailing spaces (0x20) only. This is null-terminated."]
8557 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8558 pub registration: [u8; 9],
8559}
8560impl UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
8561 pub const ENCODED_LEN: usize = 9usize;
8562 pub const DEFAULT: Self = Self {
8563 registration: [0_u8; 9usize],
8564 };
8565 #[cfg(feature = "arbitrary")]
8566 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8567 use arbitrary::{Arbitrary, Unstructured};
8568 let mut buf = [0u8; 1024];
8569 rng.fill_bytes(&mut buf);
8570 let mut unstructured = Unstructured::new(&buf);
8571 Self::arbitrary(&mut unstructured).unwrap_or_default()
8572 }
8573}
8574impl Default for UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
8575 fn default() -> Self {
8576 Self::DEFAULT.clone()
8577 }
8578}
8579impl MessageData for UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA {
8580 type Message = MavMessage;
8581 const ID: u32 = 10004u32;
8582 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG_REGISTRATION";
8583 const EXTRA_CRC: u8 = 133u8;
8584 const ENCODED_LEN: usize = 9usize;
8585 fn deser(
8586 _version: MavlinkVersion,
8587 __input: &[u8],
8588 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8589 let avail_len = __input.len();
8590 let mut payload_buf = [0; Self::ENCODED_LEN];
8591 let mut buf = if avail_len < Self::ENCODED_LEN {
8592 payload_buf[0..avail_len].copy_from_slice(__input);
8593 Bytes::new(&payload_buf)
8594 } else {
8595 Bytes::new(__input)
8596 };
8597 let mut __struct = Self::default();
8598 for v in &mut __struct.registration {
8599 let val = buf.get_u8();
8600 *v = val;
8601 }
8602 Ok(__struct)
8603 }
8604 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8605 let mut __tmp = BytesMut::new(bytes);
8606 #[allow(clippy::absurd_extreme_comparisons)]
8607 #[allow(unused_comparisons)]
8608 if __tmp.remaining() < Self::ENCODED_LEN {
8609 panic!(
8610 "buffer is too small (need {} bytes, but got {})",
8611 Self::ENCODED_LEN,
8612 __tmp.remaining(),
8613 )
8614 }
8615 for val in &self.registration {
8616 __tmp.put_u8(*val);
8617 }
8618 if matches!(version, MavlinkVersion::V2) {
8619 let len = __tmp.len();
8620 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8621 } else {
8622 __tmp.len()
8623 }
8624 }
8625}
8626#[doc = "id: 115"]
8627#[doc = "Sent from simulation to autopilot, avoids in contrast to HIL_STATE singularities. This packet is useful for high throughput applications such as hardware in the loop simulations."]
8628#[derive(Debug, Clone, PartialEq)]
8629#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8630#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8631pub struct HIL_STATE_QUATERNION_DATA {
8632 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
8633 pub time_usec: u64,
8634 #[doc = "Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)"]
8635 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8636 pub attitude_quaternion: [f32; 4],
8637 #[doc = "Body frame roll / phi angular speed"]
8638 pub rollspeed: f32,
8639 #[doc = "Body frame pitch / theta angular speed"]
8640 pub pitchspeed: f32,
8641 #[doc = "Body frame yaw / psi angular speed"]
8642 pub yawspeed: f32,
8643 #[doc = "Latitude"]
8644 pub lat: i32,
8645 #[doc = "Longitude"]
8646 pub lon: i32,
8647 #[doc = "Altitude"]
8648 pub alt: i32,
8649 #[doc = "Ground X Speed (Latitude)"]
8650 pub vx: i16,
8651 #[doc = "Ground Y Speed (Longitude)"]
8652 pub vy: i16,
8653 #[doc = "Ground Z Speed (Altitude)"]
8654 pub vz: i16,
8655 #[doc = "Indicated airspeed"]
8656 pub ind_airspeed: u16,
8657 #[doc = "True airspeed"]
8658 pub true_airspeed: u16,
8659 #[doc = "X acceleration"]
8660 pub xacc: i16,
8661 #[doc = "Y acceleration"]
8662 pub yacc: i16,
8663 #[doc = "Z acceleration"]
8664 pub zacc: i16,
8665}
8666impl HIL_STATE_QUATERNION_DATA {
8667 pub const ENCODED_LEN: usize = 64usize;
8668 pub const DEFAULT: Self = Self {
8669 time_usec: 0_u64,
8670 attitude_quaternion: [0.0_f32; 4usize],
8671 rollspeed: 0.0_f32,
8672 pitchspeed: 0.0_f32,
8673 yawspeed: 0.0_f32,
8674 lat: 0_i32,
8675 lon: 0_i32,
8676 alt: 0_i32,
8677 vx: 0_i16,
8678 vy: 0_i16,
8679 vz: 0_i16,
8680 ind_airspeed: 0_u16,
8681 true_airspeed: 0_u16,
8682 xacc: 0_i16,
8683 yacc: 0_i16,
8684 zacc: 0_i16,
8685 };
8686 #[cfg(feature = "arbitrary")]
8687 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8688 use arbitrary::{Arbitrary, Unstructured};
8689 let mut buf = [0u8; 1024];
8690 rng.fill_bytes(&mut buf);
8691 let mut unstructured = Unstructured::new(&buf);
8692 Self::arbitrary(&mut unstructured).unwrap_or_default()
8693 }
8694}
8695impl Default for HIL_STATE_QUATERNION_DATA {
8696 fn default() -> Self {
8697 Self::DEFAULT.clone()
8698 }
8699}
8700impl MessageData for HIL_STATE_QUATERNION_DATA {
8701 type Message = MavMessage;
8702 const ID: u32 = 115u32;
8703 const NAME: &'static str = "HIL_STATE_QUATERNION";
8704 const EXTRA_CRC: u8 = 4u8;
8705 const ENCODED_LEN: usize = 64usize;
8706 fn deser(
8707 _version: MavlinkVersion,
8708 __input: &[u8],
8709 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8710 let avail_len = __input.len();
8711 let mut payload_buf = [0; Self::ENCODED_LEN];
8712 let mut buf = if avail_len < Self::ENCODED_LEN {
8713 payload_buf[0..avail_len].copy_from_slice(__input);
8714 Bytes::new(&payload_buf)
8715 } else {
8716 Bytes::new(__input)
8717 };
8718 let mut __struct = Self::default();
8719 __struct.time_usec = buf.get_u64_le();
8720 for v in &mut __struct.attitude_quaternion {
8721 let val = buf.get_f32_le();
8722 *v = val;
8723 }
8724 __struct.rollspeed = buf.get_f32_le();
8725 __struct.pitchspeed = buf.get_f32_le();
8726 __struct.yawspeed = buf.get_f32_le();
8727 __struct.lat = buf.get_i32_le();
8728 __struct.lon = buf.get_i32_le();
8729 __struct.alt = buf.get_i32_le();
8730 __struct.vx = buf.get_i16_le();
8731 __struct.vy = buf.get_i16_le();
8732 __struct.vz = buf.get_i16_le();
8733 __struct.ind_airspeed = buf.get_u16_le();
8734 __struct.true_airspeed = buf.get_u16_le();
8735 __struct.xacc = buf.get_i16_le();
8736 __struct.yacc = buf.get_i16_le();
8737 __struct.zacc = buf.get_i16_le();
8738 Ok(__struct)
8739 }
8740 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8741 let mut __tmp = BytesMut::new(bytes);
8742 #[allow(clippy::absurd_extreme_comparisons)]
8743 #[allow(unused_comparisons)]
8744 if __tmp.remaining() < Self::ENCODED_LEN {
8745 panic!(
8746 "buffer is too small (need {} bytes, but got {})",
8747 Self::ENCODED_LEN,
8748 __tmp.remaining(),
8749 )
8750 }
8751 __tmp.put_u64_le(self.time_usec);
8752 for val in &self.attitude_quaternion {
8753 __tmp.put_f32_le(*val);
8754 }
8755 __tmp.put_f32_le(self.rollspeed);
8756 __tmp.put_f32_le(self.pitchspeed);
8757 __tmp.put_f32_le(self.yawspeed);
8758 __tmp.put_i32_le(self.lat);
8759 __tmp.put_i32_le(self.lon);
8760 __tmp.put_i32_le(self.alt);
8761 __tmp.put_i16_le(self.vx);
8762 __tmp.put_i16_le(self.vy);
8763 __tmp.put_i16_le(self.vz);
8764 __tmp.put_u16_le(self.ind_airspeed);
8765 __tmp.put_u16_le(self.true_airspeed);
8766 __tmp.put_i16_le(self.xacc);
8767 __tmp.put_i16_le(self.yacc);
8768 __tmp.put_i16_le(self.zacc);
8769 if matches!(version, MavlinkVersion::V2) {
8770 let len = __tmp.len();
8771 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8772 } else {
8773 __tmp.len()
8774 }
8775 }
8776}
8777#[doc = "id: 10008"]
8778#[doc = "Status message with information from UCP Heartbeat and Status messages."]
8779#[derive(Debug, Clone, PartialEq)]
8780#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8781#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8782pub struct UAVIONIX_ADSB_OUT_STATUS_DATA {
8783 #[doc = "Mode A code (typically 1200 [0x04B0] for VFR)"]
8784 pub squawk: u16,
8785 #[doc = "ADS-B transponder status state flags"]
8786 pub state: UavionixAdsbOutStatusState,
8787 #[doc = "Integrity and Accuracy of traffic reported as a 4-bit value for each field (NACp 7:4, NIC 3:0) and encoded by Containment Radius (HPL) and Estimated Position Uncertainty (HFOM), respectively"]
8788 pub NIC_NACp: UavionixAdsbOutStatusNicNacp,
8789 #[doc = "Board temperature in C"]
8790 pub boardTemp: u8,
8791 #[doc = "ADS-B transponder fault flags"]
8792 pub fault: UavionixAdsbOutStatusFault,
8793 #[doc = "Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable."]
8794 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
8795 pub flight_id: [u8; 8],
8796}
8797impl UAVIONIX_ADSB_OUT_STATUS_DATA {
8798 pub const ENCODED_LEN: usize = 14usize;
8799 pub const DEFAULT: Self = Self {
8800 squawk: 0_u16,
8801 state: UavionixAdsbOutStatusState::DEFAULT,
8802 NIC_NACp: UavionixAdsbOutStatusNicNacp::DEFAULT,
8803 boardTemp: 0_u8,
8804 fault: UavionixAdsbOutStatusFault::DEFAULT,
8805 flight_id: [0_u8; 8usize],
8806 };
8807 #[cfg(feature = "arbitrary")]
8808 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8809 use arbitrary::{Arbitrary, Unstructured};
8810 let mut buf = [0u8; 1024];
8811 rng.fill_bytes(&mut buf);
8812 let mut unstructured = Unstructured::new(&buf);
8813 Self::arbitrary(&mut unstructured).unwrap_or_default()
8814 }
8815}
8816impl Default for UAVIONIX_ADSB_OUT_STATUS_DATA {
8817 fn default() -> Self {
8818 Self::DEFAULT.clone()
8819 }
8820}
8821impl MessageData for UAVIONIX_ADSB_OUT_STATUS_DATA {
8822 type Message = MavMessage;
8823 const ID: u32 = 10008u32;
8824 const NAME: &'static str = "UAVIONIX_ADSB_OUT_STATUS";
8825 const EXTRA_CRC: u8 = 240u8;
8826 const ENCODED_LEN: usize = 14usize;
8827 fn deser(
8828 _version: MavlinkVersion,
8829 __input: &[u8],
8830 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8831 let avail_len = __input.len();
8832 let mut payload_buf = [0; Self::ENCODED_LEN];
8833 let mut buf = if avail_len < Self::ENCODED_LEN {
8834 payload_buf[0..avail_len].copy_from_slice(__input);
8835 Bytes::new(&payload_buf)
8836 } else {
8837 Bytes::new(__input)
8838 };
8839 let mut __struct = Self::default();
8840 __struct.squawk = buf.get_u16_le();
8841 let tmp = buf.get_u8();
8842 __struct.state =
8843 UavionixAdsbOutStatusState::from_bits(tmp & UavionixAdsbOutStatusState::all().bits())
8844 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8845 flag_type: "UavionixAdsbOutStatusState",
8846 value: tmp as u32,
8847 })?;
8848 let tmp = buf.get_u8();
8849 __struct.NIC_NACp =
8850 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8851 enum_type: "UavionixAdsbOutStatusNicNacp",
8852 value: tmp as u32,
8853 })?;
8854 __struct.boardTemp = buf.get_u8();
8855 let tmp = buf.get_u8();
8856 __struct.fault =
8857 UavionixAdsbOutStatusFault::from_bits(tmp & UavionixAdsbOutStatusFault::all().bits())
8858 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
8859 flag_type: "UavionixAdsbOutStatusFault",
8860 value: tmp as u32,
8861 })?;
8862 for v in &mut __struct.flight_id {
8863 let val = buf.get_u8();
8864 *v = val;
8865 }
8866 Ok(__struct)
8867 }
8868 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8869 let mut __tmp = BytesMut::new(bytes);
8870 #[allow(clippy::absurd_extreme_comparisons)]
8871 #[allow(unused_comparisons)]
8872 if __tmp.remaining() < Self::ENCODED_LEN {
8873 panic!(
8874 "buffer is too small (need {} bytes, but got {})",
8875 Self::ENCODED_LEN,
8876 __tmp.remaining(),
8877 )
8878 }
8879 __tmp.put_u16_le(self.squawk);
8880 __tmp.put_u8(self.state.bits());
8881 __tmp.put_u8(self.NIC_NACp as u8);
8882 __tmp.put_u8(self.boardTemp);
8883 __tmp.put_u8(self.fault.bits());
8884 for val in &self.flight_id {
8885 __tmp.put_u8(*val);
8886 }
8887 if matches!(version, MavlinkVersion::V2) {
8888 let len = __tmp.len();
8889 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8890 } else {
8891 __tmp.len()
8892 }
8893 }
8894}
8895#[doc = "id: 47"]
8896#[doc = "Acknowledgment message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero)."]
8897#[derive(Debug, Clone, PartialEq)]
8898#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
8899#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
8900pub struct MISSION_ACK_DATA {
8901 #[doc = "System ID"]
8902 pub target_system: u8,
8903 #[doc = "Component ID"]
8904 pub target_component: u8,
8905 #[doc = "Mission result."]
8906 pub mavtype: MavMissionResult,
8907 #[doc = "Mission type."]
8908 #[cfg_attr(feature = "serde", serde(default))]
8909 pub mission_type: MavMissionType,
8910 #[doc = "Id of new on-vehicle mission, fence, or rally point plan (on upload to vehicle). The id is calculated and returned by a vehicle when a new plan is uploaded by a GCS. The only requirement on the id is that it must change when there is any change to the on-vehicle plan type (there is no requirement that the id be globally unique). 0 on download from the vehicle to the GCS (on download the ID is set in MISSION_COUNT). 0 if plan ids are not supported. The current on-vehicle plan ids are streamed in `MISSION_CURRENT`, allowing a GCS to determine if any part of the plan has changed and needs to be re-uploaded."]
8911 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
8912 pub opaque_id: u32,
8913}
8914impl MISSION_ACK_DATA {
8915 pub const ENCODED_LEN: usize = 8usize;
8916 pub const DEFAULT: Self = Self {
8917 target_system: 0_u8,
8918 target_component: 0_u8,
8919 mavtype: MavMissionResult::DEFAULT,
8920 mission_type: MavMissionType::DEFAULT,
8921 opaque_id: 0_u32,
8922 };
8923 #[cfg(feature = "arbitrary")]
8924 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
8925 use arbitrary::{Arbitrary, Unstructured};
8926 let mut buf = [0u8; 1024];
8927 rng.fill_bytes(&mut buf);
8928 let mut unstructured = Unstructured::new(&buf);
8929 Self::arbitrary(&mut unstructured).unwrap_or_default()
8930 }
8931}
8932impl Default for MISSION_ACK_DATA {
8933 fn default() -> Self {
8934 Self::DEFAULT.clone()
8935 }
8936}
8937impl MessageData for MISSION_ACK_DATA {
8938 type Message = MavMessage;
8939 const ID: u32 = 47u32;
8940 const NAME: &'static str = "MISSION_ACK";
8941 const EXTRA_CRC: u8 = 153u8;
8942 const ENCODED_LEN: usize = 8usize;
8943 fn deser(
8944 _version: MavlinkVersion,
8945 __input: &[u8],
8946 ) -> Result<Self, ::mavlink_core::error::ParserError> {
8947 let avail_len = __input.len();
8948 let mut payload_buf = [0; Self::ENCODED_LEN];
8949 let mut buf = if avail_len < Self::ENCODED_LEN {
8950 payload_buf[0..avail_len].copy_from_slice(__input);
8951 Bytes::new(&payload_buf)
8952 } else {
8953 Bytes::new(__input)
8954 };
8955 let mut __struct = Self::default();
8956 __struct.target_system = buf.get_u8();
8957 __struct.target_component = buf.get_u8();
8958 let tmp = buf.get_u8();
8959 __struct.mavtype =
8960 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8961 enum_type: "MavMissionResult",
8962 value: tmp as u32,
8963 })?;
8964 let tmp = buf.get_u8();
8965 __struct.mission_type =
8966 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
8967 enum_type: "MavMissionType",
8968 value: tmp as u32,
8969 })?;
8970 __struct.opaque_id = buf.get_u32_le();
8971 Ok(__struct)
8972 }
8973 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
8974 let mut __tmp = BytesMut::new(bytes);
8975 #[allow(clippy::absurd_extreme_comparisons)]
8976 #[allow(unused_comparisons)]
8977 if __tmp.remaining() < Self::ENCODED_LEN {
8978 panic!(
8979 "buffer is too small (need {} bytes, but got {})",
8980 Self::ENCODED_LEN,
8981 __tmp.remaining(),
8982 )
8983 }
8984 __tmp.put_u8(self.target_system);
8985 __tmp.put_u8(self.target_component);
8986 __tmp.put_u8(self.mavtype as u8);
8987 __tmp.put_u8(self.mission_type as u8);
8988 __tmp.put_u32_le(self.opaque_id);
8989 if matches!(version, MavlinkVersion::V2) {
8990 let len = __tmp.len();
8991 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
8992 } else {
8993 __tmp.len()
8994 }
8995 }
8996}
8997#[doc = "id: 9000"]
8998#[doc = "Cumulative distance traveled for each reported wheel."]
8999#[derive(Debug, Clone, PartialEq)]
9000#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9001#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9002pub struct WHEEL_DISTANCE_DATA {
9003 #[doc = "Timestamp (synced to UNIX time or since system boot)."]
9004 pub time_usec: u64,
9005 #[doc = "Distance reported by individual wheel encoders. Forward rotations increase values, reverse rotations decrease them. Not all wheels will necessarily have wheel encoders; the mapping of encoders to wheel positions must be agreed/understood by the endpoints."]
9006 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9007 pub distance: [f64; 16],
9008 #[doc = "Number of wheels reported."]
9009 pub count: u8,
9010}
9011impl WHEEL_DISTANCE_DATA {
9012 pub const ENCODED_LEN: usize = 137usize;
9013 pub const DEFAULT: Self = Self {
9014 time_usec: 0_u64,
9015 distance: [0.0_f64; 16usize],
9016 count: 0_u8,
9017 };
9018 #[cfg(feature = "arbitrary")]
9019 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9020 use arbitrary::{Arbitrary, Unstructured};
9021 let mut buf = [0u8; 1024];
9022 rng.fill_bytes(&mut buf);
9023 let mut unstructured = Unstructured::new(&buf);
9024 Self::arbitrary(&mut unstructured).unwrap_or_default()
9025 }
9026}
9027impl Default for WHEEL_DISTANCE_DATA {
9028 fn default() -> Self {
9029 Self::DEFAULT.clone()
9030 }
9031}
9032impl MessageData for WHEEL_DISTANCE_DATA {
9033 type Message = MavMessage;
9034 const ID: u32 = 9000u32;
9035 const NAME: &'static str = "WHEEL_DISTANCE";
9036 const EXTRA_CRC: u8 = 113u8;
9037 const ENCODED_LEN: usize = 137usize;
9038 fn deser(
9039 _version: MavlinkVersion,
9040 __input: &[u8],
9041 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9042 let avail_len = __input.len();
9043 let mut payload_buf = [0; Self::ENCODED_LEN];
9044 let mut buf = if avail_len < Self::ENCODED_LEN {
9045 payload_buf[0..avail_len].copy_from_slice(__input);
9046 Bytes::new(&payload_buf)
9047 } else {
9048 Bytes::new(__input)
9049 };
9050 let mut __struct = Self::default();
9051 __struct.time_usec = buf.get_u64_le();
9052 for v in &mut __struct.distance {
9053 let val = buf.get_f64_le();
9054 *v = val;
9055 }
9056 __struct.count = buf.get_u8();
9057 Ok(__struct)
9058 }
9059 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9060 let mut __tmp = BytesMut::new(bytes);
9061 #[allow(clippy::absurd_extreme_comparisons)]
9062 #[allow(unused_comparisons)]
9063 if __tmp.remaining() < Self::ENCODED_LEN {
9064 panic!(
9065 "buffer is too small (need {} bytes, but got {})",
9066 Self::ENCODED_LEN,
9067 __tmp.remaining(),
9068 )
9069 }
9070 __tmp.put_u64_le(self.time_usec);
9071 for val in &self.distance {
9072 __tmp.put_f64_le(*val);
9073 }
9074 __tmp.put_u8(self.count);
9075 if matches!(version, MavlinkVersion::V2) {
9076 let len = __tmp.len();
9077 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9078 } else {
9079 __tmp.len()
9080 }
9081 }
9082}
9083#[doc = "id: 106"]
9084#[doc = "Optical flow from an angular rate flow sensor (e.g. PX4FLOW or mouse sensor)."]
9085#[derive(Debug, Clone, PartialEq)]
9086#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9087#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9088pub struct OPTICAL_FLOW_RAD_DATA {
9089 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
9090 pub time_usec: u64,
9091 #[doc = "Integration time. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the."]
9092 pub integration_time_us: u32,
9093 #[doc = "Flow around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)"]
9094 pub integrated_x: f32,
9095 #[doc = "Flow around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)"]
9096 pub integrated_y: f32,
9097 #[doc = "RH rotation around X axis"]
9098 pub integrated_xgyro: f32,
9099 #[doc = "RH rotation around Y axis"]
9100 pub integrated_ygyro: f32,
9101 #[doc = "RH rotation around Z axis"]
9102 pub integrated_zgyro: f32,
9103 #[doc = "Time since the distance was sampled."]
9104 pub time_delta_distance_us: u32,
9105 #[doc = "Distance to the center of the flow field. Positive value (including zero): distance known. Negative value: Unknown distance."]
9106 pub distance: f32,
9107 #[doc = "Temperature"]
9108 pub temperature: i16,
9109 #[doc = "Sensor ID"]
9110 pub sensor_id: u8,
9111 #[doc = "Optical flow quality / confidence. 0: no valid flow, 255: maximum quality"]
9112 pub quality: u8,
9113}
9114impl OPTICAL_FLOW_RAD_DATA {
9115 pub const ENCODED_LEN: usize = 44usize;
9116 pub const DEFAULT: Self = Self {
9117 time_usec: 0_u64,
9118 integration_time_us: 0_u32,
9119 integrated_x: 0.0_f32,
9120 integrated_y: 0.0_f32,
9121 integrated_xgyro: 0.0_f32,
9122 integrated_ygyro: 0.0_f32,
9123 integrated_zgyro: 0.0_f32,
9124 time_delta_distance_us: 0_u32,
9125 distance: 0.0_f32,
9126 temperature: 0_i16,
9127 sensor_id: 0_u8,
9128 quality: 0_u8,
9129 };
9130 #[cfg(feature = "arbitrary")]
9131 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9132 use arbitrary::{Arbitrary, Unstructured};
9133 let mut buf = [0u8; 1024];
9134 rng.fill_bytes(&mut buf);
9135 let mut unstructured = Unstructured::new(&buf);
9136 Self::arbitrary(&mut unstructured).unwrap_or_default()
9137 }
9138}
9139impl Default for OPTICAL_FLOW_RAD_DATA {
9140 fn default() -> Self {
9141 Self::DEFAULT.clone()
9142 }
9143}
9144impl MessageData for OPTICAL_FLOW_RAD_DATA {
9145 type Message = MavMessage;
9146 const ID: u32 = 106u32;
9147 const NAME: &'static str = "OPTICAL_FLOW_RAD";
9148 const EXTRA_CRC: u8 = 138u8;
9149 const ENCODED_LEN: usize = 44usize;
9150 fn deser(
9151 _version: MavlinkVersion,
9152 __input: &[u8],
9153 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9154 let avail_len = __input.len();
9155 let mut payload_buf = [0; Self::ENCODED_LEN];
9156 let mut buf = if avail_len < Self::ENCODED_LEN {
9157 payload_buf[0..avail_len].copy_from_slice(__input);
9158 Bytes::new(&payload_buf)
9159 } else {
9160 Bytes::new(__input)
9161 };
9162 let mut __struct = Self::default();
9163 __struct.time_usec = buf.get_u64_le();
9164 __struct.integration_time_us = buf.get_u32_le();
9165 __struct.integrated_x = buf.get_f32_le();
9166 __struct.integrated_y = buf.get_f32_le();
9167 __struct.integrated_xgyro = buf.get_f32_le();
9168 __struct.integrated_ygyro = buf.get_f32_le();
9169 __struct.integrated_zgyro = buf.get_f32_le();
9170 __struct.time_delta_distance_us = buf.get_u32_le();
9171 __struct.distance = buf.get_f32_le();
9172 __struct.temperature = buf.get_i16_le();
9173 __struct.sensor_id = buf.get_u8();
9174 __struct.quality = buf.get_u8();
9175 Ok(__struct)
9176 }
9177 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9178 let mut __tmp = BytesMut::new(bytes);
9179 #[allow(clippy::absurd_extreme_comparisons)]
9180 #[allow(unused_comparisons)]
9181 if __tmp.remaining() < Self::ENCODED_LEN {
9182 panic!(
9183 "buffer is too small (need {} bytes, but got {})",
9184 Self::ENCODED_LEN,
9185 __tmp.remaining(),
9186 )
9187 }
9188 __tmp.put_u64_le(self.time_usec);
9189 __tmp.put_u32_le(self.integration_time_us);
9190 __tmp.put_f32_le(self.integrated_x);
9191 __tmp.put_f32_le(self.integrated_y);
9192 __tmp.put_f32_le(self.integrated_xgyro);
9193 __tmp.put_f32_le(self.integrated_ygyro);
9194 __tmp.put_f32_le(self.integrated_zgyro);
9195 __tmp.put_u32_le(self.time_delta_distance_us);
9196 __tmp.put_f32_le(self.distance);
9197 __tmp.put_i16_le(self.temperature);
9198 __tmp.put_u8(self.sensor_id);
9199 __tmp.put_u8(self.quality);
9200 if matches!(version, MavlinkVersion::V2) {
9201 let len = __tmp.len();
9202 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9203 } else {
9204 __tmp.len()
9205 }
9206 }
9207}
9208#[doc = "id: 276"]
9209#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
9210#[derive(Debug, Clone, PartialEq)]
9211#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9212#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9213pub struct CAMERA_TRACKING_GEO_STATUS_DATA {
9214 #[doc = "Latitude of tracked object"]
9215 pub lat: i32,
9216 #[doc = "Longitude of tracked object"]
9217 pub lon: i32,
9218 #[doc = "Altitude of tracked object(AMSL, WGS84)"]
9219 pub alt: f32,
9220 #[doc = "Horizontal accuracy. NAN if unknown"]
9221 pub h_acc: f32,
9222 #[doc = "Vertical accuracy. NAN if unknown"]
9223 pub v_acc: f32,
9224 #[doc = "North velocity of tracked object. NAN if unknown"]
9225 pub vel_n: f32,
9226 #[doc = "East velocity of tracked object. NAN if unknown"]
9227 pub vel_e: f32,
9228 #[doc = "Down velocity of tracked object. NAN if unknown"]
9229 pub vel_d: f32,
9230 #[doc = "Velocity accuracy. NAN if unknown"]
9231 pub vel_acc: f32,
9232 #[doc = "Distance between camera and tracked object. NAN if unknown"]
9233 pub dist: f32,
9234 #[doc = "Heading in radians, in NED. NAN if unknown"]
9235 pub hdg: f32,
9236 #[doc = "Accuracy of heading, in NED. NAN if unknown"]
9237 pub hdg_acc: f32,
9238 #[doc = "Current tracking status"]
9239 pub tracking_status: CameraTrackingStatusFlags,
9240 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
9241 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9242 pub camera_device_id: u8,
9243}
9244impl CAMERA_TRACKING_GEO_STATUS_DATA {
9245 pub const ENCODED_LEN: usize = 50usize;
9246 pub const DEFAULT: Self = Self {
9247 lat: 0_i32,
9248 lon: 0_i32,
9249 alt: 0.0_f32,
9250 h_acc: 0.0_f32,
9251 v_acc: 0.0_f32,
9252 vel_n: 0.0_f32,
9253 vel_e: 0.0_f32,
9254 vel_d: 0.0_f32,
9255 vel_acc: 0.0_f32,
9256 dist: 0.0_f32,
9257 hdg: 0.0_f32,
9258 hdg_acc: 0.0_f32,
9259 tracking_status: CameraTrackingStatusFlags::DEFAULT,
9260 camera_device_id: 0_u8,
9261 };
9262 #[cfg(feature = "arbitrary")]
9263 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9264 use arbitrary::{Arbitrary, Unstructured};
9265 let mut buf = [0u8; 1024];
9266 rng.fill_bytes(&mut buf);
9267 let mut unstructured = Unstructured::new(&buf);
9268 Self::arbitrary(&mut unstructured).unwrap_or_default()
9269 }
9270}
9271impl Default for CAMERA_TRACKING_GEO_STATUS_DATA {
9272 fn default() -> Self {
9273 Self::DEFAULT.clone()
9274 }
9275}
9276impl MessageData for CAMERA_TRACKING_GEO_STATUS_DATA {
9277 type Message = MavMessage;
9278 const ID: u32 = 276u32;
9279 const NAME: &'static str = "CAMERA_TRACKING_GEO_STATUS";
9280 const EXTRA_CRC: u8 = 18u8;
9281 const ENCODED_LEN: usize = 50usize;
9282 fn deser(
9283 _version: MavlinkVersion,
9284 __input: &[u8],
9285 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9286 let avail_len = __input.len();
9287 let mut payload_buf = [0; Self::ENCODED_LEN];
9288 let mut buf = if avail_len < Self::ENCODED_LEN {
9289 payload_buf[0..avail_len].copy_from_slice(__input);
9290 Bytes::new(&payload_buf)
9291 } else {
9292 Bytes::new(__input)
9293 };
9294 let mut __struct = Self::default();
9295 __struct.lat = buf.get_i32_le();
9296 __struct.lon = buf.get_i32_le();
9297 __struct.alt = buf.get_f32_le();
9298 __struct.h_acc = buf.get_f32_le();
9299 __struct.v_acc = buf.get_f32_le();
9300 __struct.vel_n = buf.get_f32_le();
9301 __struct.vel_e = buf.get_f32_le();
9302 __struct.vel_d = buf.get_f32_le();
9303 __struct.vel_acc = buf.get_f32_le();
9304 __struct.dist = buf.get_f32_le();
9305 __struct.hdg = buf.get_f32_le();
9306 __struct.hdg_acc = buf.get_f32_le();
9307 let tmp = buf.get_u8();
9308 __struct.tracking_status =
9309 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9310 enum_type: "CameraTrackingStatusFlags",
9311 value: tmp as u32,
9312 })?;
9313 __struct.camera_device_id = buf.get_u8();
9314 Ok(__struct)
9315 }
9316 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9317 let mut __tmp = BytesMut::new(bytes);
9318 #[allow(clippy::absurd_extreme_comparisons)]
9319 #[allow(unused_comparisons)]
9320 if __tmp.remaining() < Self::ENCODED_LEN {
9321 panic!(
9322 "buffer is too small (need {} bytes, but got {})",
9323 Self::ENCODED_LEN,
9324 __tmp.remaining(),
9325 )
9326 }
9327 __tmp.put_i32_le(self.lat);
9328 __tmp.put_i32_le(self.lon);
9329 __tmp.put_f32_le(self.alt);
9330 __tmp.put_f32_le(self.h_acc);
9331 __tmp.put_f32_le(self.v_acc);
9332 __tmp.put_f32_le(self.vel_n);
9333 __tmp.put_f32_le(self.vel_e);
9334 __tmp.put_f32_le(self.vel_d);
9335 __tmp.put_f32_le(self.vel_acc);
9336 __tmp.put_f32_le(self.dist);
9337 __tmp.put_f32_le(self.hdg);
9338 __tmp.put_f32_le(self.hdg_acc);
9339 __tmp.put_u8(self.tracking_status as u8);
9340 __tmp.put_u8(self.camera_device_id);
9341 if matches!(version, MavlinkVersion::V2) {
9342 let len = __tmp.len();
9343 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9344 } else {
9345 __tmp.len()
9346 }
9347 }
9348}
9349#[doc = "id: 336"]
9350#[doc = "Configure cellular modems. This message is re-emitted as an acknowledgement by the modem. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
9351#[derive(Debug, Clone, PartialEq)]
9352#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9353#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9354pub struct CELLULAR_CONFIG_DATA {
9355 #[doc = "Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
9356 pub enable_lte: u8,
9357 #[doc = "Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
9358 pub enable_pin: u8,
9359 #[doc = "PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response."]
9360 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9361 pub pin: [u8; 16],
9362 #[doc = "New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response."]
9363 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9364 pub new_pin: [u8; 16],
9365 #[doc = "Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response."]
9366 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9367 pub apn: [u8; 32],
9368 #[doc = "Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response."]
9369 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9370 pub puk: [u8; 16],
9371 #[doc = "Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response."]
9372 pub roaming: u8,
9373 #[doc = "Message acceptance response (sent back to GS)."]
9374 pub response: CellularConfigResponse,
9375}
9376impl CELLULAR_CONFIG_DATA {
9377 pub const ENCODED_LEN: usize = 84usize;
9378 pub const DEFAULT: Self = Self {
9379 enable_lte: 0_u8,
9380 enable_pin: 0_u8,
9381 pin: [0_u8; 16usize],
9382 new_pin: [0_u8; 16usize],
9383 apn: [0_u8; 32usize],
9384 puk: [0_u8; 16usize],
9385 roaming: 0_u8,
9386 response: CellularConfigResponse::DEFAULT,
9387 };
9388 #[cfg(feature = "arbitrary")]
9389 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9390 use arbitrary::{Arbitrary, Unstructured};
9391 let mut buf = [0u8; 1024];
9392 rng.fill_bytes(&mut buf);
9393 let mut unstructured = Unstructured::new(&buf);
9394 Self::arbitrary(&mut unstructured).unwrap_or_default()
9395 }
9396}
9397impl Default for CELLULAR_CONFIG_DATA {
9398 fn default() -> Self {
9399 Self::DEFAULT.clone()
9400 }
9401}
9402impl MessageData for CELLULAR_CONFIG_DATA {
9403 type Message = MavMessage;
9404 const ID: u32 = 336u32;
9405 const NAME: &'static str = "CELLULAR_CONFIG";
9406 const EXTRA_CRC: u8 = 245u8;
9407 const ENCODED_LEN: usize = 84usize;
9408 fn deser(
9409 _version: MavlinkVersion,
9410 __input: &[u8],
9411 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9412 let avail_len = __input.len();
9413 let mut payload_buf = [0; Self::ENCODED_LEN];
9414 let mut buf = if avail_len < Self::ENCODED_LEN {
9415 payload_buf[0..avail_len].copy_from_slice(__input);
9416 Bytes::new(&payload_buf)
9417 } else {
9418 Bytes::new(__input)
9419 };
9420 let mut __struct = Self::default();
9421 __struct.enable_lte = buf.get_u8();
9422 __struct.enable_pin = buf.get_u8();
9423 for v in &mut __struct.pin {
9424 let val = buf.get_u8();
9425 *v = val;
9426 }
9427 for v in &mut __struct.new_pin {
9428 let val = buf.get_u8();
9429 *v = val;
9430 }
9431 for v in &mut __struct.apn {
9432 let val = buf.get_u8();
9433 *v = val;
9434 }
9435 for v in &mut __struct.puk {
9436 let val = buf.get_u8();
9437 *v = val;
9438 }
9439 __struct.roaming = buf.get_u8();
9440 let tmp = buf.get_u8();
9441 __struct.response =
9442 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9443 enum_type: "CellularConfigResponse",
9444 value: tmp as u32,
9445 })?;
9446 Ok(__struct)
9447 }
9448 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9449 let mut __tmp = BytesMut::new(bytes);
9450 #[allow(clippy::absurd_extreme_comparisons)]
9451 #[allow(unused_comparisons)]
9452 if __tmp.remaining() < Self::ENCODED_LEN {
9453 panic!(
9454 "buffer is too small (need {} bytes, but got {})",
9455 Self::ENCODED_LEN,
9456 __tmp.remaining(),
9457 )
9458 }
9459 __tmp.put_u8(self.enable_lte);
9460 __tmp.put_u8(self.enable_pin);
9461 for val in &self.pin {
9462 __tmp.put_u8(*val);
9463 }
9464 for val in &self.new_pin {
9465 __tmp.put_u8(*val);
9466 }
9467 for val in &self.apn {
9468 __tmp.put_u8(*val);
9469 }
9470 for val in &self.puk {
9471 __tmp.put_u8(*val);
9472 }
9473 __tmp.put_u8(self.roaming);
9474 __tmp.put_u8(self.response as u8);
9475 if matches!(version, MavlinkVersion::V2) {
9476 let len = __tmp.len();
9477 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9478 } else {
9479 __tmp.len()
9480 }
9481 }
9482}
9483#[doc = "id: 67"]
9484#[doc = "Data stream status information."]
9485#[derive(Debug, Clone, PartialEq)]
9486#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9487#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9488pub struct DATA_STREAM_DATA {
9489 #[doc = "The message rate"]
9490 pub message_rate: u16,
9491 #[doc = "The ID of the requested data stream"]
9492 pub stream_id: u8,
9493 #[doc = "1 stream is enabled, 0 stream is stopped."]
9494 pub on_off: u8,
9495}
9496impl DATA_STREAM_DATA {
9497 pub const ENCODED_LEN: usize = 4usize;
9498 pub const DEFAULT: Self = Self {
9499 message_rate: 0_u16,
9500 stream_id: 0_u8,
9501 on_off: 0_u8,
9502 };
9503 #[cfg(feature = "arbitrary")]
9504 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9505 use arbitrary::{Arbitrary, Unstructured};
9506 let mut buf = [0u8; 1024];
9507 rng.fill_bytes(&mut buf);
9508 let mut unstructured = Unstructured::new(&buf);
9509 Self::arbitrary(&mut unstructured).unwrap_or_default()
9510 }
9511}
9512impl Default for DATA_STREAM_DATA {
9513 fn default() -> Self {
9514 Self::DEFAULT.clone()
9515 }
9516}
9517impl MessageData for DATA_STREAM_DATA {
9518 type Message = MavMessage;
9519 const ID: u32 = 67u32;
9520 const NAME: &'static str = "DATA_STREAM";
9521 const EXTRA_CRC: u8 = 21u8;
9522 const ENCODED_LEN: usize = 4usize;
9523 fn deser(
9524 _version: MavlinkVersion,
9525 __input: &[u8],
9526 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9527 let avail_len = __input.len();
9528 let mut payload_buf = [0; Self::ENCODED_LEN];
9529 let mut buf = if avail_len < Self::ENCODED_LEN {
9530 payload_buf[0..avail_len].copy_from_slice(__input);
9531 Bytes::new(&payload_buf)
9532 } else {
9533 Bytes::new(__input)
9534 };
9535 let mut __struct = Self::default();
9536 __struct.message_rate = buf.get_u16_le();
9537 __struct.stream_id = buf.get_u8();
9538 __struct.on_off = buf.get_u8();
9539 Ok(__struct)
9540 }
9541 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9542 let mut __tmp = BytesMut::new(bytes);
9543 #[allow(clippy::absurd_extreme_comparisons)]
9544 #[allow(unused_comparisons)]
9545 if __tmp.remaining() < Self::ENCODED_LEN {
9546 panic!(
9547 "buffer is too small (need {} bytes, but got {})",
9548 Self::ENCODED_LEN,
9549 __tmp.remaining(),
9550 )
9551 }
9552 __tmp.put_u16_le(self.message_rate);
9553 __tmp.put_u8(self.stream_id);
9554 __tmp.put_u8(self.on_off);
9555 if matches!(version, MavlinkVersion::V2) {
9556 let len = __tmp.len();
9557 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9558 } else {
9559 __tmp.len()
9560 }
9561 }
9562}
9563#[doc = "id: 23"]
9564#[doc = "Set a parameter value (write new value to permanent storage). The receiving component should acknowledge the new parameter value by broadcasting a PARAM_VALUE message (broadcasting ensures that multiple GCS all have an up-to-date list of all parameters). If the sending GCS did not receive a PARAM_VALUE within its timeout time, it should re-send the PARAM_SET message. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
9565#[derive(Debug, Clone, PartialEq)]
9566#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9567#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9568pub struct PARAM_SET_DATA {
9569 #[doc = "Onboard parameter value"]
9570 pub param_value: f32,
9571 #[doc = "System ID"]
9572 pub target_system: u8,
9573 #[doc = "Component ID"]
9574 pub target_component: u8,
9575 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
9576 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9577 pub param_id: [u8; 16],
9578 #[doc = "Onboard parameter type."]
9579 pub param_type: MavParamType,
9580}
9581impl PARAM_SET_DATA {
9582 pub const ENCODED_LEN: usize = 23usize;
9583 pub const DEFAULT: Self = Self {
9584 param_value: 0.0_f32,
9585 target_system: 0_u8,
9586 target_component: 0_u8,
9587 param_id: [0_u8; 16usize],
9588 param_type: MavParamType::DEFAULT,
9589 };
9590 #[cfg(feature = "arbitrary")]
9591 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9592 use arbitrary::{Arbitrary, Unstructured};
9593 let mut buf = [0u8; 1024];
9594 rng.fill_bytes(&mut buf);
9595 let mut unstructured = Unstructured::new(&buf);
9596 Self::arbitrary(&mut unstructured).unwrap_or_default()
9597 }
9598}
9599impl Default for PARAM_SET_DATA {
9600 fn default() -> Self {
9601 Self::DEFAULT.clone()
9602 }
9603}
9604impl MessageData for PARAM_SET_DATA {
9605 type Message = MavMessage;
9606 const ID: u32 = 23u32;
9607 const NAME: &'static str = "PARAM_SET";
9608 const EXTRA_CRC: u8 = 168u8;
9609 const ENCODED_LEN: usize = 23usize;
9610 fn deser(
9611 _version: MavlinkVersion,
9612 __input: &[u8],
9613 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9614 let avail_len = __input.len();
9615 let mut payload_buf = [0; Self::ENCODED_LEN];
9616 let mut buf = if avail_len < Self::ENCODED_LEN {
9617 payload_buf[0..avail_len].copy_from_slice(__input);
9618 Bytes::new(&payload_buf)
9619 } else {
9620 Bytes::new(__input)
9621 };
9622 let mut __struct = Self::default();
9623 __struct.param_value = buf.get_f32_le();
9624 __struct.target_system = buf.get_u8();
9625 __struct.target_component = buf.get_u8();
9626 for v in &mut __struct.param_id {
9627 let val = buf.get_u8();
9628 *v = val;
9629 }
9630 let tmp = buf.get_u8();
9631 __struct.param_type =
9632 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9633 enum_type: "MavParamType",
9634 value: tmp as u32,
9635 })?;
9636 Ok(__struct)
9637 }
9638 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9639 let mut __tmp = BytesMut::new(bytes);
9640 #[allow(clippy::absurd_extreme_comparisons)]
9641 #[allow(unused_comparisons)]
9642 if __tmp.remaining() < Self::ENCODED_LEN {
9643 panic!(
9644 "buffer is too small (need {} bytes, but got {})",
9645 Self::ENCODED_LEN,
9646 __tmp.remaining(),
9647 )
9648 }
9649 __tmp.put_f32_le(self.param_value);
9650 __tmp.put_u8(self.target_system);
9651 __tmp.put_u8(self.target_component);
9652 for val in &self.param_id {
9653 __tmp.put_u8(*val);
9654 }
9655 __tmp.put_u8(self.param_type as u8);
9656 if matches!(version, MavlinkVersion::V2) {
9657 let len = __tmp.len();
9658 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9659 } else {
9660 __tmp.len()
9661 }
9662 }
9663}
9664#[doc = "id: 310"]
9665#[doc = "General status information of an UAVCAN node. Please refer to the definition of the UAVCAN message \"uavcan.protocol.NodeStatus\" for the background information. The UAVCAN specification is available at <http://uavcan.org>."]
9666#[derive(Debug, Clone, PartialEq)]
9667#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9668#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9669pub struct UAVCAN_NODE_STATUS_DATA {
9670 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
9671 pub time_usec: u64,
9672 #[doc = "Time since the start-up of the node."]
9673 pub uptime_sec: u32,
9674 #[doc = "Vendor-specific status information."]
9675 pub vendor_specific_status_code: u16,
9676 #[doc = "Generalized node health status."]
9677 pub health: UavcanNodeHealth,
9678 #[doc = "Generalized operating mode."]
9679 pub mode: UavcanNodeMode,
9680 #[doc = "Not used currently."]
9681 pub sub_mode: u8,
9682}
9683impl UAVCAN_NODE_STATUS_DATA {
9684 pub const ENCODED_LEN: usize = 17usize;
9685 pub const DEFAULT: Self = Self {
9686 time_usec: 0_u64,
9687 uptime_sec: 0_u32,
9688 vendor_specific_status_code: 0_u16,
9689 health: UavcanNodeHealth::DEFAULT,
9690 mode: UavcanNodeMode::DEFAULT,
9691 sub_mode: 0_u8,
9692 };
9693 #[cfg(feature = "arbitrary")]
9694 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9695 use arbitrary::{Arbitrary, Unstructured};
9696 let mut buf = [0u8; 1024];
9697 rng.fill_bytes(&mut buf);
9698 let mut unstructured = Unstructured::new(&buf);
9699 Self::arbitrary(&mut unstructured).unwrap_or_default()
9700 }
9701}
9702impl Default for UAVCAN_NODE_STATUS_DATA {
9703 fn default() -> Self {
9704 Self::DEFAULT.clone()
9705 }
9706}
9707impl MessageData for UAVCAN_NODE_STATUS_DATA {
9708 type Message = MavMessage;
9709 const ID: u32 = 310u32;
9710 const NAME: &'static str = "UAVCAN_NODE_STATUS";
9711 const EXTRA_CRC: u8 = 28u8;
9712 const ENCODED_LEN: usize = 17usize;
9713 fn deser(
9714 _version: MavlinkVersion,
9715 __input: &[u8],
9716 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9717 let avail_len = __input.len();
9718 let mut payload_buf = [0; Self::ENCODED_LEN];
9719 let mut buf = if avail_len < Self::ENCODED_LEN {
9720 payload_buf[0..avail_len].copy_from_slice(__input);
9721 Bytes::new(&payload_buf)
9722 } else {
9723 Bytes::new(__input)
9724 };
9725 let mut __struct = Self::default();
9726 __struct.time_usec = buf.get_u64_le();
9727 __struct.uptime_sec = buf.get_u32_le();
9728 __struct.vendor_specific_status_code = buf.get_u16_le();
9729 let tmp = buf.get_u8();
9730 __struct.health =
9731 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9732 enum_type: "UavcanNodeHealth",
9733 value: tmp as u32,
9734 })?;
9735 let tmp = buf.get_u8();
9736 __struct.mode =
9737 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9738 enum_type: "UavcanNodeMode",
9739 value: tmp as u32,
9740 })?;
9741 __struct.sub_mode = buf.get_u8();
9742 Ok(__struct)
9743 }
9744 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9745 let mut __tmp = BytesMut::new(bytes);
9746 #[allow(clippy::absurd_extreme_comparisons)]
9747 #[allow(unused_comparisons)]
9748 if __tmp.remaining() < Self::ENCODED_LEN {
9749 panic!(
9750 "buffer is too small (need {} bytes, but got {})",
9751 Self::ENCODED_LEN,
9752 __tmp.remaining(),
9753 )
9754 }
9755 __tmp.put_u64_le(self.time_usec);
9756 __tmp.put_u32_le(self.uptime_sec);
9757 __tmp.put_u16_le(self.vendor_specific_status_code);
9758 __tmp.put_u8(self.health as u8);
9759 __tmp.put_u8(self.mode as u8);
9760 __tmp.put_u8(self.sub_mode);
9761 if matches!(version, MavlinkVersion::V2) {
9762 let len = __tmp.len();
9763 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9764 } else {
9765 __tmp.len()
9766 }
9767 }
9768}
9769#[doc = "id: 261"]
9770#[doc = "Information about a storage medium. This message is sent in response to a request with MAV_CMD_REQUEST_MESSAGE and whenever the status of the storage changes (STORAGE_STATUS). Use MAV_CMD_REQUEST_MESSAGE.param2 to indicate the index/id of requested storage: 0 for all, 1 for first, 2 for second, etc."]
9771#[derive(Debug, Clone, PartialEq)]
9772#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9773#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9774pub struct STORAGE_INFORMATION_DATA {
9775 #[doc = "Timestamp (time since system boot)."]
9776 pub time_boot_ms: u32,
9777 #[doc = "Total capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
9778 pub total_capacity: f32,
9779 #[doc = "Used capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
9780 pub used_capacity: f32,
9781 #[doc = "Available storage capacity. If storage is not ready (STORAGE_STATUS_READY) value will be ignored."]
9782 pub available_capacity: f32,
9783 #[doc = "Read speed."]
9784 pub read_speed: f32,
9785 #[doc = "Write speed."]
9786 pub write_speed: f32,
9787 #[doc = "Storage ID (1 for first, 2 for second, etc.)"]
9788 pub storage_id: u8,
9789 #[doc = "Number of storage devices"]
9790 pub storage_count: u8,
9791 #[doc = "Status of storage"]
9792 pub status: StorageStatus,
9793 #[doc = "Type of storage"]
9794 #[cfg_attr(feature = "serde", serde(default))]
9795 pub mavtype: StorageType,
9796 #[doc = "Textual storage name to be used in UI (microSD 1, Internal Memory, etc.) This is a NULL terminated string. If it is exactly 32 characters long, add a terminating NULL. If this string is empty, the generic type is shown to the user."]
9797 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
9798 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
9799 pub name: [u8; 32],
9800 #[doc = "Flags indicating whether this instance is preferred storage for photos, videos, etc. Note: Implementations should initially set the flags on the system-default storage id used for saving media (if possible/supported). This setting can then be overridden using MAV_CMD_SET_STORAGE_USAGE. If the media usage flags are not set, a GCS may assume storage ID 1 is the default storage for all media types."]
9801 #[cfg_attr(feature = "serde", serde(default))]
9802 pub storage_usage: StorageUsageFlag,
9803}
9804impl STORAGE_INFORMATION_DATA {
9805 pub const ENCODED_LEN: usize = 61usize;
9806 pub const DEFAULT: Self = Self {
9807 time_boot_ms: 0_u32,
9808 total_capacity: 0.0_f32,
9809 used_capacity: 0.0_f32,
9810 available_capacity: 0.0_f32,
9811 read_speed: 0.0_f32,
9812 write_speed: 0.0_f32,
9813 storage_id: 0_u8,
9814 storage_count: 0_u8,
9815 status: StorageStatus::DEFAULT,
9816 mavtype: StorageType::DEFAULT,
9817 name: [0_u8; 32usize],
9818 storage_usage: StorageUsageFlag::DEFAULT,
9819 };
9820 #[cfg(feature = "arbitrary")]
9821 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9822 use arbitrary::{Arbitrary, Unstructured};
9823 let mut buf = [0u8; 1024];
9824 rng.fill_bytes(&mut buf);
9825 let mut unstructured = Unstructured::new(&buf);
9826 Self::arbitrary(&mut unstructured).unwrap_or_default()
9827 }
9828}
9829impl Default for STORAGE_INFORMATION_DATA {
9830 fn default() -> Self {
9831 Self::DEFAULT.clone()
9832 }
9833}
9834impl MessageData for STORAGE_INFORMATION_DATA {
9835 type Message = MavMessage;
9836 const ID: u32 = 261u32;
9837 const NAME: &'static str = "STORAGE_INFORMATION";
9838 const EXTRA_CRC: u8 = 179u8;
9839 const ENCODED_LEN: usize = 61usize;
9840 fn deser(
9841 _version: MavlinkVersion,
9842 __input: &[u8],
9843 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9844 let avail_len = __input.len();
9845 let mut payload_buf = [0; Self::ENCODED_LEN];
9846 let mut buf = if avail_len < Self::ENCODED_LEN {
9847 payload_buf[0..avail_len].copy_from_slice(__input);
9848 Bytes::new(&payload_buf)
9849 } else {
9850 Bytes::new(__input)
9851 };
9852 let mut __struct = Self::default();
9853 __struct.time_boot_ms = buf.get_u32_le();
9854 __struct.total_capacity = buf.get_f32_le();
9855 __struct.used_capacity = buf.get_f32_le();
9856 __struct.available_capacity = buf.get_f32_le();
9857 __struct.read_speed = buf.get_f32_le();
9858 __struct.write_speed = buf.get_f32_le();
9859 __struct.storage_id = buf.get_u8();
9860 __struct.storage_count = buf.get_u8();
9861 let tmp = buf.get_u8();
9862 __struct.status =
9863 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9864 enum_type: "StorageStatus",
9865 value: tmp as u32,
9866 })?;
9867 let tmp = buf.get_u8();
9868 __struct.mavtype =
9869 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9870 enum_type: "StorageType",
9871 value: tmp as u32,
9872 })?;
9873 for v in &mut __struct.name {
9874 let val = buf.get_u8();
9875 *v = val;
9876 }
9877 let tmp = buf.get_u8();
9878 __struct.storage_usage = StorageUsageFlag::from_bits(tmp & StorageUsageFlag::all().bits())
9879 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
9880 flag_type: "StorageUsageFlag",
9881 value: tmp as u32,
9882 })?;
9883 Ok(__struct)
9884 }
9885 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9886 let mut __tmp = BytesMut::new(bytes);
9887 #[allow(clippy::absurd_extreme_comparisons)]
9888 #[allow(unused_comparisons)]
9889 if __tmp.remaining() < Self::ENCODED_LEN {
9890 panic!(
9891 "buffer is too small (need {} bytes, but got {})",
9892 Self::ENCODED_LEN,
9893 __tmp.remaining(),
9894 )
9895 }
9896 __tmp.put_u32_le(self.time_boot_ms);
9897 __tmp.put_f32_le(self.total_capacity);
9898 __tmp.put_f32_le(self.used_capacity);
9899 __tmp.put_f32_le(self.available_capacity);
9900 __tmp.put_f32_le(self.read_speed);
9901 __tmp.put_f32_le(self.write_speed);
9902 __tmp.put_u8(self.storage_id);
9903 __tmp.put_u8(self.storage_count);
9904 __tmp.put_u8(self.status as u8);
9905 __tmp.put_u8(self.mavtype as u8);
9906 for val in &self.name {
9907 __tmp.put_u8(*val);
9908 }
9909 __tmp.put_u8(self.storage_usage.bits());
9910 if matches!(version, MavlinkVersion::V2) {
9911 let len = __tmp.len();
9912 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
9913 } else {
9914 __tmp.len()
9915 }
9916 }
9917}
9918#[doc = "id: 51"]
9919#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM_INT message. <https://mavlink.io/en/services/mission.html>."]
9920#[derive(Debug, Clone, PartialEq)]
9921#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
9922#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
9923pub struct MISSION_REQUEST_INT_DATA {
9924 #[doc = "Sequence"]
9925 pub seq: u16,
9926 #[doc = "System ID"]
9927 pub target_system: u8,
9928 #[doc = "Component ID"]
9929 pub target_component: u8,
9930 #[doc = "Mission type."]
9931 #[cfg_attr(feature = "serde", serde(default))]
9932 pub mission_type: MavMissionType,
9933}
9934impl MISSION_REQUEST_INT_DATA {
9935 pub const ENCODED_LEN: usize = 5usize;
9936 pub const DEFAULT: Self = Self {
9937 seq: 0_u16,
9938 target_system: 0_u8,
9939 target_component: 0_u8,
9940 mission_type: MavMissionType::DEFAULT,
9941 };
9942 #[cfg(feature = "arbitrary")]
9943 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
9944 use arbitrary::{Arbitrary, Unstructured};
9945 let mut buf = [0u8; 1024];
9946 rng.fill_bytes(&mut buf);
9947 let mut unstructured = Unstructured::new(&buf);
9948 Self::arbitrary(&mut unstructured).unwrap_or_default()
9949 }
9950}
9951impl Default for MISSION_REQUEST_INT_DATA {
9952 fn default() -> Self {
9953 Self::DEFAULT.clone()
9954 }
9955}
9956impl MessageData for MISSION_REQUEST_INT_DATA {
9957 type Message = MavMessage;
9958 const ID: u32 = 51u32;
9959 const NAME: &'static str = "MISSION_REQUEST_INT";
9960 const EXTRA_CRC: u8 = 196u8;
9961 const ENCODED_LEN: usize = 5usize;
9962 fn deser(
9963 _version: MavlinkVersion,
9964 __input: &[u8],
9965 ) -> Result<Self, ::mavlink_core::error::ParserError> {
9966 let avail_len = __input.len();
9967 let mut payload_buf = [0; Self::ENCODED_LEN];
9968 let mut buf = if avail_len < Self::ENCODED_LEN {
9969 payload_buf[0..avail_len].copy_from_slice(__input);
9970 Bytes::new(&payload_buf)
9971 } else {
9972 Bytes::new(__input)
9973 };
9974 let mut __struct = Self::default();
9975 __struct.seq = buf.get_u16_le();
9976 __struct.target_system = buf.get_u8();
9977 __struct.target_component = buf.get_u8();
9978 let tmp = buf.get_u8();
9979 __struct.mission_type =
9980 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
9981 enum_type: "MavMissionType",
9982 value: tmp as u32,
9983 })?;
9984 Ok(__struct)
9985 }
9986 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
9987 let mut __tmp = BytesMut::new(bytes);
9988 #[allow(clippy::absurd_extreme_comparisons)]
9989 #[allow(unused_comparisons)]
9990 if __tmp.remaining() < Self::ENCODED_LEN {
9991 panic!(
9992 "buffer is too small (need {} bytes, but got {})",
9993 Self::ENCODED_LEN,
9994 __tmp.remaining(),
9995 )
9996 }
9997 __tmp.put_u16_le(self.seq);
9998 __tmp.put_u8(self.target_system);
9999 __tmp.put_u8(self.target_component);
10000 __tmp.put_u8(self.mission_type as u8);
10001 if matches!(version, MavlinkVersion::V2) {
10002 let len = __tmp.len();
10003 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10004 } else {
10005 __tmp.len()
10006 }
10007 }
10008}
10009#[doc = "id: 29"]
10010#[doc = "The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field."]
10011#[derive(Debug, Clone, PartialEq)]
10012#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10013#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10014pub struct SCALED_PRESSURE_DATA {
10015 #[doc = "Timestamp (time since system boot)."]
10016 pub time_boot_ms: u32,
10017 #[doc = "Absolute pressure"]
10018 pub press_abs: f32,
10019 #[doc = "Differential pressure 1"]
10020 pub press_diff: f32,
10021 #[doc = "Absolute pressure temperature"]
10022 pub temperature: i16,
10023 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
10024 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10025 pub temperature_press_diff: i16,
10026}
10027impl SCALED_PRESSURE_DATA {
10028 pub const ENCODED_LEN: usize = 16usize;
10029 pub const DEFAULT: Self = Self {
10030 time_boot_ms: 0_u32,
10031 press_abs: 0.0_f32,
10032 press_diff: 0.0_f32,
10033 temperature: 0_i16,
10034 temperature_press_diff: 0_i16,
10035 };
10036 #[cfg(feature = "arbitrary")]
10037 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10038 use arbitrary::{Arbitrary, Unstructured};
10039 let mut buf = [0u8; 1024];
10040 rng.fill_bytes(&mut buf);
10041 let mut unstructured = Unstructured::new(&buf);
10042 Self::arbitrary(&mut unstructured).unwrap_or_default()
10043 }
10044}
10045impl Default for SCALED_PRESSURE_DATA {
10046 fn default() -> Self {
10047 Self::DEFAULT.clone()
10048 }
10049}
10050impl MessageData for SCALED_PRESSURE_DATA {
10051 type Message = MavMessage;
10052 const ID: u32 = 29u32;
10053 const NAME: &'static str = "SCALED_PRESSURE";
10054 const EXTRA_CRC: u8 = 115u8;
10055 const ENCODED_LEN: usize = 16usize;
10056 fn deser(
10057 _version: MavlinkVersion,
10058 __input: &[u8],
10059 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10060 let avail_len = __input.len();
10061 let mut payload_buf = [0; Self::ENCODED_LEN];
10062 let mut buf = if avail_len < Self::ENCODED_LEN {
10063 payload_buf[0..avail_len].copy_from_slice(__input);
10064 Bytes::new(&payload_buf)
10065 } else {
10066 Bytes::new(__input)
10067 };
10068 let mut __struct = Self::default();
10069 __struct.time_boot_ms = buf.get_u32_le();
10070 __struct.press_abs = buf.get_f32_le();
10071 __struct.press_diff = buf.get_f32_le();
10072 __struct.temperature = buf.get_i16_le();
10073 __struct.temperature_press_diff = buf.get_i16_le();
10074 Ok(__struct)
10075 }
10076 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10077 let mut __tmp = BytesMut::new(bytes);
10078 #[allow(clippy::absurd_extreme_comparisons)]
10079 #[allow(unused_comparisons)]
10080 if __tmp.remaining() < Self::ENCODED_LEN {
10081 panic!(
10082 "buffer is too small (need {} bytes, but got {})",
10083 Self::ENCODED_LEN,
10084 __tmp.remaining(),
10085 )
10086 }
10087 __tmp.put_u32_le(self.time_boot_ms);
10088 __tmp.put_f32_le(self.press_abs);
10089 __tmp.put_f32_le(self.press_diff);
10090 __tmp.put_i16_le(self.temperature);
10091 __tmp.put_i16_le(self.temperature_press_diff);
10092 if matches!(version, MavlinkVersion::V2) {
10093 let len = __tmp.len();
10094 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10095 } else {
10096 __tmp.len()
10097 }
10098 }
10099}
10100#[doc = "id: 131"]
10101#[doc = "Data packet for images sent using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
10102#[derive(Debug, Clone, PartialEq)]
10103#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10104#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10105pub struct ENCAPSULATED_DATA_DATA {
10106 #[doc = "sequence number (starting with 0 on every transmission)"]
10107 pub seqnr: u16,
10108 #[doc = "image data bytes"]
10109 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10110 pub data: [u8; 253],
10111}
10112impl ENCAPSULATED_DATA_DATA {
10113 pub const ENCODED_LEN: usize = 255usize;
10114 pub const DEFAULT: Self = Self {
10115 seqnr: 0_u16,
10116 data: [0_u8; 253usize],
10117 };
10118 #[cfg(feature = "arbitrary")]
10119 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10120 use arbitrary::{Arbitrary, Unstructured};
10121 let mut buf = [0u8; 1024];
10122 rng.fill_bytes(&mut buf);
10123 let mut unstructured = Unstructured::new(&buf);
10124 Self::arbitrary(&mut unstructured).unwrap_or_default()
10125 }
10126}
10127impl Default for ENCAPSULATED_DATA_DATA {
10128 fn default() -> Self {
10129 Self::DEFAULT.clone()
10130 }
10131}
10132impl MessageData for ENCAPSULATED_DATA_DATA {
10133 type Message = MavMessage;
10134 const ID: u32 = 131u32;
10135 const NAME: &'static str = "ENCAPSULATED_DATA";
10136 const EXTRA_CRC: u8 = 223u8;
10137 const ENCODED_LEN: usize = 255usize;
10138 fn deser(
10139 _version: MavlinkVersion,
10140 __input: &[u8],
10141 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10142 let avail_len = __input.len();
10143 let mut payload_buf = [0; Self::ENCODED_LEN];
10144 let mut buf = if avail_len < Self::ENCODED_LEN {
10145 payload_buf[0..avail_len].copy_from_slice(__input);
10146 Bytes::new(&payload_buf)
10147 } else {
10148 Bytes::new(__input)
10149 };
10150 let mut __struct = Self::default();
10151 __struct.seqnr = buf.get_u16_le();
10152 for v in &mut __struct.data {
10153 let val = buf.get_u8();
10154 *v = val;
10155 }
10156 Ok(__struct)
10157 }
10158 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10159 let mut __tmp = BytesMut::new(bytes);
10160 #[allow(clippy::absurd_extreme_comparisons)]
10161 #[allow(unused_comparisons)]
10162 if __tmp.remaining() < Self::ENCODED_LEN {
10163 panic!(
10164 "buffer is too small (need {} bytes, but got {})",
10165 Self::ENCODED_LEN,
10166 __tmp.remaining(),
10167 )
10168 }
10169 __tmp.put_u16_le(self.seqnr);
10170 for val in &self.data {
10171 __tmp.put_u8(*val);
10172 }
10173 if matches!(version, MavlinkVersion::V2) {
10174 let len = __tmp.len();
10175 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10176 } else {
10177 __tmp.len()
10178 }
10179 }
10180}
10181#[doc = "id: 258"]
10182#[doc = "Control vehicle tone generation (buzzer)."]
10183#[derive(Debug, Clone, PartialEq)]
10184#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10185#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10186pub struct PLAY_TUNE_DATA {
10187 #[doc = "System ID"]
10188 pub target_system: u8,
10189 #[doc = "Component ID"]
10190 pub target_component: u8,
10191 #[doc = "tune in board specific format"]
10192 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10193 pub tune: [u8; 30],
10194 #[doc = "tune extension (appended to tune)"]
10195 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
10196 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10197 pub tune2: [u8; 200],
10198}
10199impl PLAY_TUNE_DATA {
10200 pub const ENCODED_LEN: usize = 232usize;
10201 pub const DEFAULT: Self = Self {
10202 target_system: 0_u8,
10203 target_component: 0_u8,
10204 tune: [0_u8; 30usize],
10205 tune2: [0_u8; 200usize],
10206 };
10207 #[cfg(feature = "arbitrary")]
10208 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10209 use arbitrary::{Arbitrary, Unstructured};
10210 let mut buf = [0u8; 1024];
10211 rng.fill_bytes(&mut buf);
10212 let mut unstructured = Unstructured::new(&buf);
10213 Self::arbitrary(&mut unstructured).unwrap_or_default()
10214 }
10215}
10216impl Default for PLAY_TUNE_DATA {
10217 fn default() -> Self {
10218 Self::DEFAULT.clone()
10219 }
10220}
10221impl MessageData for PLAY_TUNE_DATA {
10222 type Message = MavMessage;
10223 const ID: u32 = 258u32;
10224 const NAME: &'static str = "PLAY_TUNE";
10225 const EXTRA_CRC: u8 = 187u8;
10226 const ENCODED_LEN: usize = 232usize;
10227 fn deser(
10228 _version: MavlinkVersion,
10229 __input: &[u8],
10230 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10231 let avail_len = __input.len();
10232 let mut payload_buf = [0; Self::ENCODED_LEN];
10233 let mut buf = if avail_len < Self::ENCODED_LEN {
10234 payload_buf[0..avail_len].copy_from_slice(__input);
10235 Bytes::new(&payload_buf)
10236 } else {
10237 Bytes::new(__input)
10238 };
10239 let mut __struct = Self::default();
10240 __struct.target_system = buf.get_u8();
10241 __struct.target_component = buf.get_u8();
10242 for v in &mut __struct.tune {
10243 let val = buf.get_u8();
10244 *v = val;
10245 }
10246 for v in &mut __struct.tune2 {
10247 let val = buf.get_u8();
10248 *v = val;
10249 }
10250 Ok(__struct)
10251 }
10252 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10253 let mut __tmp = BytesMut::new(bytes);
10254 #[allow(clippy::absurd_extreme_comparisons)]
10255 #[allow(unused_comparisons)]
10256 if __tmp.remaining() < Self::ENCODED_LEN {
10257 panic!(
10258 "buffer is too small (need {} bytes, but got {})",
10259 Self::ENCODED_LEN,
10260 __tmp.remaining(),
10261 )
10262 }
10263 __tmp.put_u8(self.target_system);
10264 __tmp.put_u8(self.target_component);
10265 for val in &self.tune {
10266 __tmp.put_u8(*val);
10267 }
10268 for val in &self.tune2 {
10269 __tmp.put_u8(*val);
10270 }
10271 if matches!(version, MavlinkVersion::V2) {
10272 let len = __tmp.len();
10273 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10274 } else {
10275 __tmp.len()
10276 }
10277 }
10278}
10279#[doc = "id: 387"]
10280#[doc = "A forwarded CANFD frame as requested by MAV_CMD_CAN_FORWARD. These are separated from CAN_FRAME as they need different handling (eg. TAO handling)."]
10281#[derive(Debug, Clone, PartialEq)]
10282#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10283#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10284pub struct CANFD_FRAME_DATA {
10285 #[doc = "Frame ID"]
10286 pub id: u32,
10287 #[doc = "System ID."]
10288 pub target_system: u8,
10289 #[doc = "Component ID."]
10290 pub target_component: u8,
10291 #[doc = "bus number"]
10292 pub bus: u8,
10293 #[doc = "Frame length"]
10294 pub len: u8,
10295 #[doc = "Frame data"]
10296 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10297 pub data: [u8; 64],
10298}
10299impl CANFD_FRAME_DATA {
10300 pub const ENCODED_LEN: usize = 72usize;
10301 pub const DEFAULT: Self = Self {
10302 id: 0_u32,
10303 target_system: 0_u8,
10304 target_component: 0_u8,
10305 bus: 0_u8,
10306 len: 0_u8,
10307 data: [0_u8; 64usize],
10308 };
10309 #[cfg(feature = "arbitrary")]
10310 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10311 use arbitrary::{Arbitrary, Unstructured};
10312 let mut buf = [0u8; 1024];
10313 rng.fill_bytes(&mut buf);
10314 let mut unstructured = Unstructured::new(&buf);
10315 Self::arbitrary(&mut unstructured).unwrap_or_default()
10316 }
10317}
10318impl Default for CANFD_FRAME_DATA {
10319 fn default() -> Self {
10320 Self::DEFAULT.clone()
10321 }
10322}
10323impl MessageData for CANFD_FRAME_DATA {
10324 type Message = MavMessage;
10325 const ID: u32 = 387u32;
10326 const NAME: &'static str = "CANFD_FRAME";
10327 const EXTRA_CRC: u8 = 4u8;
10328 const ENCODED_LEN: usize = 72usize;
10329 fn deser(
10330 _version: MavlinkVersion,
10331 __input: &[u8],
10332 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10333 let avail_len = __input.len();
10334 let mut payload_buf = [0; Self::ENCODED_LEN];
10335 let mut buf = if avail_len < Self::ENCODED_LEN {
10336 payload_buf[0..avail_len].copy_from_slice(__input);
10337 Bytes::new(&payload_buf)
10338 } else {
10339 Bytes::new(__input)
10340 };
10341 let mut __struct = Self::default();
10342 __struct.id = buf.get_u32_le();
10343 __struct.target_system = buf.get_u8();
10344 __struct.target_component = buf.get_u8();
10345 __struct.bus = buf.get_u8();
10346 __struct.len = buf.get_u8();
10347 for v in &mut __struct.data {
10348 let val = buf.get_u8();
10349 *v = val;
10350 }
10351 Ok(__struct)
10352 }
10353 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10354 let mut __tmp = BytesMut::new(bytes);
10355 #[allow(clippy::absurd_extreme_comparisons)]
10356 #[allow(unused_comparisons)]
10357 if __tmp.remaining() < Self::ENCODED_LEN {
10358 panic!(
10359 "buffer is too small (need {} bytes, but got {})",
10360 Self::ENCODED_LEN,
10361 __tmp.remaining(),
10362 )
10363 }
10364 __tmp.put_u32_le(self.id);
10365 __tmp.put_u8(self.target_system);
10366 __tmp.put_u8(self.target_component);
10367 __tmp.put_u8(self.bus);
10368 __tmp.put_u8(self.len);
10369 for val in &self.data {
10370 __tmp.put_u8(*val);
10371 }
10372 if matches!(version, MavlinkVersion::V2) {
10373 let len = __tmp.len();
10374 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10375 } else {
10376 __tmp.len()
10377 }
10378 }
10379}
10380#[doc = "id: 437"]
10381#[doc = "A change to the sequence number indicates that the set of AVAILABLE_MODES has changed. A receiver must re-request all available modes whenever the sequence number changes. This is only emitted after the first change and should then be broadcast at low rate (nominally 0.3 Hz) and on change. See <https://mavlink.io/en/services/standard_modes.html>."]
10382#[derive(Debug, Clone, PartialEq)]
10383#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10384#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10385pub struct AVAILABLE_MODES_MONITOR_DATA {
10386 #[doc = "Sequence number. The value iterates sequentially whenever AVAILABLE_MODES changes (e.g. support for a new mode is added/removed dynamically)."]
10387 pub seq: u8,
10388}
10389impl AVAILABLE_MODES_MONITOR_DATA {
10390 pub const ENCODED_LEN: usize = 1usize;
10391 pub const DEFAULT: Self = Self { seq: 0_u8 };
10392 #[cfg(feature = "arbitrary")]
10393 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10394 use arbitrary::{Arbitrary, Unstructured};
10395 let mut buf = [0u8; 1024];
10396 rng.fill_bytes(&mut buf);
10397 let mut unstructured = Unstructured::new(&buf);
10398 Self::arbitrary(&mut unstructured).unwrap_or_default()
10399 }
10400}
10401impl Default for AVAILABLE_MODES_MONITOR_DATA {
10402 fn default() -> Self {
10403 Self::DEFAULT.clone()
10404 }
10405}
10406impl MessageData for AVAILABLE_MODES_MONITOR_DATA {
10407 type Message = MavMessage;
10408 const ID: u32 = 437u32;
10409 const NAME: &'static str = "AVAILABLE_MODES_MONITOR";
10410 const EXTRA_CRC: u8 = 30u8;
10411 const ENCODED_LEN: usize = 1usize;
10412 fn deser(
10413 _version: MavlinkVersion,
10414 __input: &[u8],
10415 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10416 let avail_len = __input.len();
10417 let mut payload_buf = [0; Self::ENCODED_LEN];
10418 let mut buf = if avail_len < Self::ENCODED_LEN {
10419 payload_buf[0..avail_len].copy_from_slice(__input);
10420 Bytes::new(&payload_buf)
10421 } else {
10422 Bytes::new(__input)
10423 };
10424 let mut __struct = Self::default();
10425 __struct.seq = buf.get_u8();
10426 Ok(__struct)
10427 }
10428 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10429 let mut __tmp = BytesMut::new(bytes);
10430 #[allow(clippy::absurd_extreme_comparisons)]
10431 #[allow(unused_comparisons)]
10432 if __tmp.remaining() < Self::ENCODED_LEN {
10433 panic!(
10434 "buffer is too small (need {} bytes, but got {})",
10435 Self::ENCODED_LEN,
10436 __tmp.remaining(),
10437 )
10438 }
10439 __tmp.put_u8(self.seq);
10440 if matches!(version, MavlinkVersion::V2) {
10441 let len = __tmp.len();
10442 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10443 } else {
10444 __tmp.len()
10445 }
10446 }
10447}
10448#[doc = "id: 254"]
10449#[doc = "Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N."]
10450#[derive(Debug, Clone, PartialEq)]
10451#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10452#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10453pub struct DEBUG_DATA {
10454 #[doc = "Timestamp (time since system boot)."]
10455 pub time_boot_ms: u32,
10456 #[doc = "DEBUG value"]
10457 pub value: f32,
10458 #[doc = "index of debug variable"]
10459 pub ind: u8,
10460}
10461impl DEBUG_DATA {
10462 pub const ENCODED_LEN: usize = 9usize;
10463 pub const DEFAULT: Self = Self {
10464 time_boot_ms: 0_u32,
10465 value: 0.0_f32,
10466 ind: 0_u8,
10467 };
10468 #[cfg(feature = "arbitrary")]
10469 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10470 use arbitrary::{Arbitrary, Unstructured};
10471 let mut buf = [0u8; 1024];
10472 rng.fill_bytes(&mut buf);
10473 let mut unstructured = Unstructured::new(&buf);
10474 Self::arbitrary(&mut unstructured).unwrap_or_default()
10475 }
10476}
10477impl Default for DEBUG_DATA {
10478 fn default() -> Self {
10479 Self::DEFAULT.clone()
10480 }
10481}
10482impl MessageData for DEBUG_DATA {
10483 type Message = MavMessage;
10484 const ID: u32 = 254u32;
10485 const NAME: &'static str = "DEBUG";
10486 const EXTRA_CRC: u8 = 46u8;
10487 const ENCODED_LEN: usize = 9usize;
10488 fn deser(
10489 _version: MavlinkVersion,
10490 __input: &[u8],
10491 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10492 let avail_len = __input.len();
10493 let mut payload_buf = [0; Self::ENCODED_LEN];
10494 let mut buf = if avail_len < Self::ENCODED_LEN {
10495 payload_buf[0..avail_len].copy_from_slice(__input);
10496 Bytes::new(&payload_buf)
10497 } else {
10498 Bytes::new(__input)
10499 };
10500 let mut __struct = Self::default();
10501 __struct.time_boot_ms = buf.get_u32_le();
10502 __struct.value = buf.get_f32_le();
10503 __struct.ind = buf.get_u8();
10504 Ok(__struct)
10505 }
10506 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10507 let mut __tmp = BytesMut::new(bytes);
10508 #[allow(clippy::absurd_extreme_comparisons)]
10509 #[allow(unused_comparisons)]
10510 if __tmp.remaining() < Self::ENCODED_LEN {
10511 panic!(
10512 "buffer is too small (need {} bytes, but got {})",
10513 Self::ENCODED_LEN,
10514 __tmp.remaining(),
10515 )
10516 }
10517 __tmp.put_u32_le(self.time_boot_ms);
10518 __tmp.put_f32_le(self.value);
10519 __tmp.put_u8(self.ind);
10520 if matches!(version, MavlinkVersion::V2) {
10521 let len = __tmp.len();
10522 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10523 } else {
10524 __tmp.len()
10525 }
10526 }
10527}
10528#[doc = "id: 386"]
10529#[doc = "A forwarded CAN frame as requested by MAV_CMD_CAN_FORWARD."]
10530#[derive(Debug, Clone, PartialEq)]
10531#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10532#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10533pub struct CAN_FRAME_DATA {
10534 #[doc = "Frame ID"]
10535 pub id: u32,
10536 #[doc = "System ID."]
10537 pub target_system: u8,
10538 #[doc = "Component ID."]
10539 pub target_component: u8,
10540 #[doc = "Bus number"]
10541 pub bus: u8,
10542 #[doc = "Frame length"]
10543 pub len: u8,
10544 #[doc = "Frame data"]
10545 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10546 pub data: [u8; 8],
10547}
10548impl CAN_FRAME_DATA {
10549 pub const ENCODED_LEN: usize = 16usize;
10550 pub const DEFAULT: Self = Self {
10551 id: 0_u32,
10552 target_system: 0_u8,
10553 target_component: 0_u8,
10554 bus: 0_u8,
10555 len: 0_u8,
10556 data: [0_u8; 8usize],
10557 };
10558 #[cfg(feature = "arbitrary")]
10559 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10560 use arbitrary::{Arbitrary, Unstructured};
10561 let mut buf = [0u8; 1024];
10562 rng.fill_bytes(&mut buf);
10563 let mut unstructured = Unstructured::new(&buf);
10564 Self::arbitrary(&mut unstructured).unwrap_or_default()
10565 }
10566}
10567impl Default for CAN_FRAME_DATA {
10568 fn default() -> Self {
10569 Self::DEFAULT.clone()
10570 }
10571}
10572impl MessageData for CAN_FRAME_DATA {
10573 type Message = MavMessage;
10574 const ID: u32 = 386u32;
10575 const NAME: &'static str = "CAN_FRAME";
10576 const EXTRA_CRC: u8 = 132u8;
10577 const ENCODED_LEN: usize = 16usize;
10578 fn deser(
10579 _version: MavlinkVersion,
10580 __input: &[u8],
10581 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10582 let avail_len = __input.len();
10583 let mut payload_buf = [0; Self::ENCODED_LEN];
10584 let mut buf = if avail_len < Self::ENCODED_LEN {
10585 payload_buf[0..avail_len].copy_from_slice(__input);
10586 Bytes::new(&payload_buf)
10587 } else {
10588 Bytes::new(__input)
10589 };
10590 let mut __struct = Self::default();
10591 __struct.id = buf.get_u32_le();
10592 __struct.target_system = buf.get_u8();
10593 __struct.target_component = buf.get_u8();
10594 __struct.bus = buf.get_u8();
10595 __struct.len = buf.get_u8();
10596 for v in &mut __struct.data {
10597 let val = buf.get_u8();
10598 *v = val;
10599 }
10600 Ok(__struct)
10601 }
10602 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10603 let mut __tmp = BytesMut::new(bytes);
10604 #[allow(clippy::absurd_extreme_comparisons)]
10605 #[allow(unused_comparisons)]
10606 if __tmp.remaining() < Self::ENCODED_LEN {
10607 panic!(
10608 "buffer is too small (need {} bytes, but got {})",
10609 Self::ENCODED_LEN,
10610 __tmp.remaining(),
10611 )
10612 }
10613 __tmp.put_u32_le(self.id);
10614 __tmp.put_u8(self.target_system);
10615 __tmp.put_u8(self.target_component);
10616 __tmp.put_u8(self.bus);
10617 __tmp.put_u8(self.len);
10618 for val in &self.data {
10619 __tmp.put_u8(*val);
10620 }
10621 if matches!(version, MavlinkVersion::V2) {
10622 let len = __tmp.len();
10623 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10624 } else {
10625 __tmp.len()
10626 }
10627 }
10628}
10629#[doc = "id: 81"]
10630#[doc = "Setpoint in roll, pitch, yaw and thrust from the operator."]
10631#[derive(Debug, Clone, PartialEq)]
10632#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10633#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10634pub struct MANUAL_SETPOINT_DATA {
10635 #[doc = "Timestamp (time since system boot)."]
10636 pub time_boot_ms: u32,
10637 #[doc = "Desired roll rate"]
10638 pub roll: f32,
10639 #[doc = "Desired pitch rate"]
10640 pub pitch: f32,
10641 #[doc = "Desired yaw rate"]
10642 pub yaw: f32,
10643 #[doc = "Collective thrust, normalized to 0 .. 1"]
10644 pub thrust: f32,
10645 #[doc = "Flight mode switch position, 0.. 255"]
10646 pub mode_switch: u8,
10647 #[doc = "Override mode switch position, 0.. 255"]
10648 pub manual_override_switch: u8,
10649}
10650impl MANUAL_SETPOINT_DATA {
10651 pub const ENCODED_LEN: usize = 22usize;
10652 pub const DEFAULT: Self = Self {
10653 time_boot_ms: 0_u32,
10654 roll: 0.0_f32,
10655 pitch: 0.0_f32,
10656 yaw: 0.0_f32,
10657 thrust: 0.0_f32,
10658 mode_switch: 0_u8,
10659 manual_override_switch: 0_u8,
10660 };
10661 #[cfg(feature = "arbitrary")]
10662 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10663 use arbitrary::{Arbitrary, Unstructured};
10664 let mut buf = [0u8; 1024];
10665 rng.fill_bytes(&mut buf);
10666 let mut unstructured = Unstructured::new(&buf);
10667 Self::arbitrary(&mut unstructured).unwrap_or_default()
10668 }
10669}
10670impl Default for MANUAL_SETPOINT_DATA {
10671 fn default() -> Self {
10672 Self::DEFAULT.clone()
10673 }
10674}
10675impl MessageData for MANUAL_SETPOINT_DATA {
10676 type Message = MavMessage;
10677 const ID: u32 = 81u32;
10678 const NAME: &'static str = "MANUAL_SETPOINT";
10679 const EXTRA_CRC: u8 = 106u8;
10680 const ENCODED_LEN: usize = 22usize;
10681 fn deser(
10682 _version: MavlinkVersion,
10683 __input: &[u8],
10684 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10685 let avail_len = __input.len();
10686 let mut payload_buf = [0; Self::ENCODED_LEN];
10687 let mut buf = if avail_len < Self::ENCODED_LEN {
10688 payload_buf[0..avail_len].copy_from_slice(__input);
10689 Bytes::new(&payload_buf)
10690 } else {
10691 Bytes::new(__input)
10692 };
10693 let mut __struct = Self::default();
10694 __struct.time_boot_ms = buf.get_u32_le();
10695 __struct.roll = buf.get_f32_le();
10696 __struct.pitch = buf.get_f32_le();
10697 __struct.yaw = buf.get_f32_le();
10698 __struct.thrust = buf.get_f32_le();
10699 __struct.mode_switch = buf.get_u8();
10700 __struct.manual_override_switch = buf.get_u8();
10701 Ok(__struct)
10702 }
10703 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10704 let mut __tmp = BytesMut::new(bytes);
10705 #[allow(clippy::absurd_extreme_comparisons)]
10706 #[allow(unused_comparisons)]
10707 if __tmp.remaining() < Self::ENCODED_LEN {
10708 panic!(
10709 "buffer is too small (need {} bytes, but got {})",
10710 Self::ENCODED_LEN,
10711 __tmp.remaining(),
10712 )
10713 }
10714 __tmp.put_u32_le(self.time_boot_ms);
10715 __tmp.put_f32_le(self.roll);
10716 __tmp.put_f32_le(self.pitch);
10717 __tmp.put_f32_le(self.yaw);
10718 __tmp.put_f32_le(self.thrust);
10719 __tmp.put_u8(self.mode_switch);
10720 __tmp.put_u8(self.manual_override_switch);
10721 if matches!(version, MavlinkVersion::V2) {
10722 let len = __tmp.len();
10723 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10724 } else {
10725 __tmp.len()
10726 }
10727 }
10728}
10729#[doc = "id: 41"]
10730#[doc = "Set the mission item with sequence number seq as the current item and emit MISSION_CURRENT (whether or not the mission number changed). If a mission is currently being executed, the system will continue to this new mission item on the shortest path, skipping any intermediate mission items. Note that mission jump repeat counters are not reset (see MAV_CMD_DO_JUMP param2). This message may trigger a mission state-machine change on some systems: for example from MISSION_STATE_NOT_STARTED or MISSION_STATE_PAUSED to MISSION_STATE_ACTIVE. If the system is in mission mode, on those systems this command might therefore start, restart or resume the mission. If the system is not in mission mode this message must not trigger a switch to mission mode."]
10731#[derive(Debug, Clone, PartialEq)]
10732#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10733#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10734pub struct MISSION_SET_CURRENT_DATA {
10735 #[doc = "Sequence"]
10736 pub seq: u16,
10737 #[doc = "System ID"]
10738 pub target_system: u8,
10739 #[doc = "Component ID"]
10740 pub target_component: u8,
10741}
10742impl MISSION_SET_CURRENT_DATA {
10743 pub const ENCODED_LEN: usize = 4usize;
10744 pub const DEFAULT: Self = Self {
10745 seq: 0_u16,
10746 target_system: 0_u8,
10747 target_component: 0_u8,
10748 };
10749 #[cfg(feature = "arbitrary")]
10750 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10751 use arbitrary::{Arbitrary, Unstructured};
10752 let mut buf = [0u8; 1024];
10753 rng.fill_bytes(&mut buf);
10754 let mut unstructured = Unstructured::new(&buf);
10755 Self::arbitrary(&mut unstructured).unwrap_or_default()
10756 }
10757}
10758impl Default for MISSION_SET_CURRENT_DATA {
10759 fn default() -> Self {
10760 Self::DEFAULT.clone()
10761 }
10762}
10763impl MessageData for MISSION_SET_CURRENT_DATA {
10764 type Message = MavMessage;
10765 const ID: u32 = 41u32;
10766 const NAME: &'static str = "MISSION_SET_CURRENT";
10767 const EXTRA_CRC: u8 = 28u8;
10768 const ENCODED_LEN: usize = 4usize;
10769 fn deser(
10770 _version: MavlinkVersion,
10771 __input: &[u8],
10772 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10773 let avail_len = __input.len();
10774 let mut payload_buf = [0; Self::ENCODED_LEN];
10775 let mut buf = if avail_len < Self::ENCODED_LEN {
10776 payload_buf[0..avail_len].copy_from_slice(__input);
10777 Bytes::new(&payload_buf)
10778 } else {
10779 Bytes::new(__input)
10780 };
10781 let mut __struct = Self::default();
10782 __struct.seq = buf.get_u16_le();
10783 __struct.target_system = buf.get_u8();
10784 __struct.target_component = buf.get_u8();
10785 Ok(__struct)
10786 }
10787 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10788 let mut __tmp = BytesMut::new(bytes);
10789 #[allow(clippy::absurd_extreme_comparisons)]
10790 #[allow(unused_comparisons)]
10791 if __tmp.remaining() < Self::ENCODED_LEN {
10792 panic!(
10793 "buffer is too small (need {} bytes, but got {})",
10794 Self::ENCODED_LEN,
10795 __tmp.remaining(),
10796 )
10797 }
10798 __tmp.put_u16_le(self.seq);
10799 __tmp.put_u8(self.target_system);
10800 __tmp.put_u8(self.target_component);
10801 if matches!(version, MavlinkVersion::V2) {
10802 let len = __tmp.len();
10803 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10804 } else {
10805 __tmp.len()
10806 }
10807 }
10808}
10809#[doc = "id: 257"]
10810#[doc = "Report button state change."]
10811#[derive(Debug, Clone, PartialEq)]
10812#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10813#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10814pub struct BUTTON_CHANGE_DATA {
10815 #[doc = "Timestamp (time since system boot)."]
10816 pub time_boot_ms: u32,
10817 #[doc = "Time of last change of button state."]
10818 pub last_change_ms: u32,
10819 #[doc = "Bitmap for state of buttons."]
10820 pub state: u8,
10821}
10822impl BUTTON_CHANGE_DATA {
10823 pub const ENCODED_LEN: usize = 9usize;
10824 pub const DEFAULT: Self = Self {
10825 time_boot_ms: 0_u32,
10826 last_change_ms: 0_u32,
10827 state: 0_u8,
10828 };
10829 #[cfg(feature = "arbitrary")]
10830 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10831 use arbitrary::{Arbitrary, Unstructured};
10832 let mut buf = [0u8; 1024];
10833 rng.fill_bytes(&mut buf);
10834 let mut unstructured = Unstructured::new(&buf);
10835 Self::arbitrary(&mut unstructured).unwrap_or_default()
10836 }
10837}
10838impl Default for BUTTON_CHANGE_DATA {
10839 fn default() -> Self {
10840 Self::DEFAULT.clone()
10841 }
10842}
10843impl MessageData for BUTTON_CHANGE_DATA {
10844 type Message = MavMessage;
10845 const ID: u32 = 257u32;
10846 const NAME: &'static str = "BUTTON_CHANGE";
10847 const EXTRA_CRC: u8 = 131u8;
10848 const ENCODED_LEN: usize = 9usize;
10849 fn deser(
10850 _version: MavlinkVersion,
10851 __input: &[u8],
10852 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10853 let avail_len = __input.len();
10854 let mut payload_buf = [0; Self::ENCODED_LEN];
10855 let mut buf = if avail_len < Self::ENCODED_LEN {
10856 payload_buf[0..avail_len].copy_from_slice(__input);
10857 Bytes::new(&payload_buf)
10858 } else {
10859 Bytes::new(__input)
10860 };
10861 let mut __struct = Self::default();
10862 __struct.time_boot_ms = buf.get_u32_le();
10863 __struct.last_change_ms = buf.get_u32_le();
10864 __struct.state = buf.get_u8();
10865 Ok(__struct)
10866 }
10867 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10868 let mut __tmp = BytesMut::new(bytes);
10869 #[allow(clippy::absurd_extreme_comparisons)]
10870 #[allow(unused_comparisons)]
10871 if __tmp.remaining() < Self::ENCODED_LEN {
10872 panic!(
10873 "buffer is too small (need {} bytes, but got {})",
10874 Self::ENCODED_LEN,
10875 __tmp.remaining(),
10876 )
10877 }
10878 __tmp.put_u32_le(self.time_boot_ms);
10879 __tmp.put_u32_le(self.last_change_ms);
10880 __tmp.put_u8(self.state);
10881 if matches!(version, MavlinkVersion::V2) {
10882 let len = __tmp.len();
10883 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10884 } else {
10885 __tmp.len()
10886 }
10887 }
10888}
10889#[doc = "id: 388"]
10890#[doc = "Modify the filter of what CAN messages to forward over the mavlink. This can be used to make CAN forwarding work well on low bandwidth links. The filtering is applied on bits 8 to 24 of the CAN id (2nd and 3rd bytes) which corresponds to the DroneCAN message ID for DroneCAN. Filters with more than 16 IDs can be constructed by sending multiple CAN_FILTER_MODIFY messages."]
10891#[derive(Debug, Clone, PartialEq)]
10892#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10893#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
10894pub struct CAN_FILTER_MODIFY_DATA {
10895 #[doc = "filter IDs, length num_ids"]
10896 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
10897 pub ids: [u16; 16],
10898 #[doc = "System ID."]
10899 pub target_system: u8,
10900 #[doc = "Component ID."]
10901 pub target_component: u8,
10902 #[doc = "bus number"]
10903 pub bus: u8,
10904 #[doc = "what operation to perform on the filter list. See CAN_FILTER_OP enum."]
10905 pub operation: CanFilterOp,
10906 #[doc = "number of IDs in filter list"]
10907 pub num_ids: u8,
10908}
10909impl CAN_FILTER_MODIFY_DATA {
10910 pub const ENCODED_LEN: usize = 37usize;
10911 pub const DEFAULT: Self = Self {
10912 ids: [0_u16; 16usize],
10913 target_system: 0_u8,
10914 target_component: 0_u8,
10915 bus: 0_u8,
10916 operation: CanFilterOp::DEFAULT,
10917 num_ids: 0_u8,
10918 };
10919 #[cfg(feature = "arbitrary")]
10920 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
10921 use arbitrary::{Arbitrary, Unstructured};
10922 let mut buf = [0u8; 1024];
10923 rng.fill_bytes(&mut buf);
10924 let mut unstructured = Unstructured::new(&buf);
10925 Self::arbitrary(&mut unstructured).unwrap_or_default()
10926 }
10927}
10928impl Default for CAN_FILTER_MODIFY_DATA {
10929 fn default() -> Self {
10930 Self::DEFAULT.clone()
10931 }
10932}
10933impl MessageData for CAN_FILTER_MODIFY_DATA {
10934 type Message = MavMessage;
10935 const ID: u32 = 388u32;
10936 const NAME: &'static str = "CAN_FILTER_MODIFY";
10937 const EXTRA_CRC: u8 = 8u8;
10938 const ENCODED_LEN: usize = 37usize;
10939 fn deser(
10940 _version: MavlinkVersion,
10941 __input: &[u8],
10942 ) -> Result<Self, ::mavlink_core::error::ParserError> {
10943 let avail_len = __input.len();
10944 let mut payload_buf = [0; Self::ENCODED_LEN];
10945 let mut buf = if avail_len < Self::ENCODED_LEN {
10946 payload_buf[0..avail_len].copy_from_slice(__input);
10947 Bytes::new(&payload_buf)
10948 } else {
10949 Bytes::new(__input)
10950 };
10951 let mut __struct = Self::default();
10952 for v in &mut __struct.ids {
10953 let val = buf.get_u16_le();
10954 *v = val;
10955 }
10956 __struct.target_system = buf.get_u8();
10957 __struct.target_component = buf.get_u8();
10958 __struct.bus = buf.get_u8();
10959 let tmp = buf.get_u8();
10960 __struct.operation =
10961 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
10962 enum_type: "CanFilterOp",
10963 value: tmp as u32,
10964 })?;
10965 __struct.num_ids = buf.get_u8();
10966 Ok(__struct)
10967 }
10968 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
10969 let mut __tmp = BytesMut::new(bytes);
10970 #[allow(clippy::absurd_extreme_comparisons)]
10971 #[allow(unused_comparisons)]
10972 if __tmp.remaining() < Self::ENCODED_LEN {
10973 panic!(
10974 "buffer is too small (need {} bytes, but got {})",
10975 Self::ENCODED_LEN,
10976 __tmp.remaining(),
10977 )
10978 }
10979 for val in &self.ids {
10980 __tmp.put_u16_le(*val);
10981 }
10982 __tmp.put_u8(self.target_system);
10983 __tmp.put_u8(self.target_component);
10984 __tmp.put_u8(self.bus);
10985 __tmp.put_u8(self.operation as u8);
10986 __tmp.put_u8(self.num_ids);
10987 if matches!(version, MavlinkVersion::V2) {
10988 let len = __tmp.len();
10989 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
10990 } else {
10991 __tmp.len()
10992 }
10993 }
10994}
10995#[doc = "id: 120"]
10996#[doc = "Reply to LOG_REQUEST_DATA."]
10997#[derive(Debug, Clone, PartialEq)]
10998#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
10999#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11000pub struct LOG_DATA_DATA {
11001 #[doc = "Offset into the log"]
11002 pub ofs: u32,
11003 #[doc = "Log id (from LOG_ENTRY reply)"]
11004 pub id: u16,
11005 #[doc = "Number of bytes (zero for end of log)"]
11006 pub count: u8,
11007 #[doc = "log data"]
11008 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11009 pub data: [u8; 90],
11010}
11011impl LOG_DATA_DATA {
11012 pub const ENCODED_LEN: usize = 97usize;
11013 pub const DEFAULT: Self = Self {
11014 ofs: 0_u32,
11015 id: 0_u16,
11016 count: 0_u8,
11017 data: [0_u8; 90usize],
11018 };
11019 #[cfg(feature = "arbitrary")]
11020 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11021 use arbitrary::{Arbitrary, Unstructured};
11022 let mut buf = [0u8; 1024];
11023 rng.fill_bytes(&mut buf);
11024 let mut unstructured = Unstructured::new(&buf);
11025 Self::arbitrary(&mut unstructured).unwrap_or_default()
11026 }
11027}
11028impl Default for LOG_DATA_DATA {
11029 fn default() -> Self {
11030 Self::DEFAULT.clone()
11031 }
11032}
11033impl MessageData for LOG_DATA_DATA {
11034 type Message = MavMessage;
11035 const ID: u32 = 120u32;
11036 const NAME: &'static str = "LOG_DATA";
11037 const EXTRA_CRC: u8 = 134u8;
11038 const ENCODED_LEN: usize = 97usize;
11039 fn deser(
11040 _version: MavlinkVersion,
11041 __input: &[u8],
11042 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11043 let avail_len = __input.len();
11044 let mut payload_buf = [0; Self::ENCODED_LEN];
11045 let mut buf = if avail_len < Self::ENCODED_LEN {
11046 payload_buf[0..avail_len].copy_from_slice(__input);
11047 Bytes::new(&payload_buf)
11048 } else {
11049 Bytes::new(__input)
11050 };
11051 let mut __struct = Self::default();
11052 __struct.ofs = buf.get_u32_le();
11053 __struct.id = buf.get_u16_le();
11054 __struct.count = buf.get_u8();
11055 for v in &mut __struct.data {
11056 let val = buf.get_u8();
11057 *v = val;
11058 }
11059 Ok(__struct)
11060 }
11061 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11062 let mut __tmp = BytesMut::new(bytes);
11063 #[allow(clippy::absurd_extreme_comparisons)]
11064 #[allow(unused_comparisons)]
11065 if __tmp.remaining() < Self::ENCODED_LEN {
11066 panic!(
11067 "buffer is too small (need {} bytes, but got {})",
11068 Self::ENCODED_LEN,
11069 __tmp.remaining(),
11070 )
11071 }
11072 __tmp.put_u32_le(self.ofs);
11073 __tmp.put_u16_le(self.id);
11074 __tmp.put_u8(self.count);
11075 for val in &self.data {
11076 __tmp.put_u8(*val);
11077 }
11078 if matches!(version, MavlinkVersion::V2) {
11079 let len = __tmp.len();
11080 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11081 } else {
11082 __tmp.len()
11083 }
11084 }
11085}
11086#[doc = "id: 250"]
11087#[doc = "To debug something using a named 3D vector."]
11088#[derive(Debug, Clone, PartialEq)]
11089#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11090#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11091pub struct DEBUG_VECT_DATA {
11092 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
11093 pub time_usec: u64,
11094 #[doc = "x"]
11095 pub x: f32,
11096 #[doc = "y"]
11097 pub y: f32,
11098 #[doc = "z"]
11099 pub z: f32,
11100 #[doc = "Name"]
11101 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11102 pub name: [u8; 10],
11103}
11104impl DEBUG_VECT_DATA {
11105 pub const ENCODED_LEN: usize = 30usize;
11106 pub const DEFAULT: Self = Self {
11107 time_usec: 0_u64,
11108 x: 0.0_f32,
11109 y: 0.0_f32,
11110 z: 0.0_f32,
11111 name: [0_u8; 10usize],
11112 };
11113 #[cfg(feature = "arbitrary")]
11114 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11115 use arbitrary::{Arbitrary, Unstructured};
11116 let mut buf = [0u8; 1024];
11117 rng.fill_bytes(&mut buf);
11118 let mut unstructured = Unstructured::new(&buf);
11119 Self::arbitrary(&mut unstructured).unwrap_or_default()
11120 }
11121}
11122impl Default for DEBUG_VECT_DATA {
11123 fn default() -> Self {
11124 Self::DEFAULT.clone()
11125 }
11126}
11127impl MessageData for DEBUG_VECT_DATA {
11128 type Message = MavMessage;
11129 const ID: u32 = 250u32;
11130 const NAME: &'static str = "DEBUG_VECT";
11131 const EXTRA_CRC: u8 = 49u8;
11132 const ENCODED_LEN: usize = 30usize;
11133 fn deser(
11134 _version: MavlinkVersion,
11135 __input: &[u8],
11136 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11137 let avail_len = __input.len();
11138 let mut payload_buf = [0; Self::ENCODED_LEN];
11139 let mut buf = if avail_len < Self::ENCODED_LEN {
11140 payload_buf[0..avail_len].copy_from_slice(__input);
11141 Bytes::new(&payload_buf)
11142 } else {
11143 Bytes::new(__input)
11144 };
11145 let mut __struct = Self::default();
11146 __struct.time_usec = buf.get_u64_le();
11147 __struct.x = buf.get_f32_le();
11148 __struct.y = buf.get_f32_le();
11149 __struct.z = buf.get_f32_le();
11150 for v in &mut __struct.name {
11151 let val = buf.get_u8();
11152 *v = val;
11153 }
11154 Ok(__struct)
11155 }
11156 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11157 let mut __tmp = BytesMut::new(bytes);
11158 #[allow(clippy::absurd_extreme_comparisons)]
11159 #[allow(unused_comparisons)]
11160 if __tmp.remaining() < Self::ENCODED_LEN {
11161 panic!(
11162 "buffer is too small (need {} bytes, but got {})",
11163 Self::ENCODED_LEN,
11164 __tmp.remaining(),
11165 )
11166 }
11167 __tmp.put_u64_le(self.time_usec);
11168 __tmp.put_f32_le(self.x);
11169 __tmp.put_f32_le(self.y);
11170 __tmp.put_f32_le(self.z);
11171 for val in &self.name {
11172 __tmp.put_u8(*val);
11173 }
11174 if matches!(version, MavlinkVersion::V2) {
11175 let len = __tmp.len();
11176 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11177 } else {
11178 __tmp.len()
11179 }
11180 }
11181}
11182#[doc = "id: 400"]
11183#[doc = "Play vehicle tone/tune (buzzer). Supersedes message PLAY_TUNE."]
11184#[derive(Debug, Clone, PartialEq)]
11185#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11186#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11187pub struct PLAY_TUNE_V2_DATA {
11188 #[doc = "Tune format"]
11189 pub format: TuneFormat,
11190 #[doc = "System ID"]
11191 pub target_system: u8,
11192 #[doc = "Component ID"]
11193 pub target_component: u8,
11194 #[doc = "Tune definition as a NULL-terminated string."]
11195 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11196 pub tune: [u8; 248],
11197}
11198impl PLAY_TUNE_V2_DATA {
11199 pub const ENCODED_LEN: usize = 254usize;
11200 pub const DEFAULT: Self = Self {
11201 format: TuneFormat::DEFAULT,
11202 target_system: 0_u8,
11203 target_component: 0_u8,
11204 tune: [0_u8; 248usize],
11205 };
11206 #[cfg(feature = "arbitrary")]
11207 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11208 use arbitrary::{Arbitrary, Unstructured};
11209 let mut buf = [0u8; 1024];
11210 rng.fill_bytes(&mut buf);
11211 let mut unstructured = Unstructured::new(&buf);
11212 Self::arbitrary(&mut unstructured).unwrap_or_default()
11213 }
11214}
11215impl Default for PLAY_TUNE_V2_DATA {
11216 fn default() -> Self {
11217 Self::DEFAULT.clone()
11218 }
11219}
11220impl MessageData for PLAY_TUNE_V2_DATA {
11221 type Message = MavMessage;
11222 const ID: u32 = 400u32;
11223 const NAME: &'static str = "PLAY_TUNE_V2";
11224 const EXTRA_CRC: u8 = 110u8;
11225 const ENCODED_LEN: usize = 254usize;
11226 fn deser(
11227 _version: MavlinkVersion,
11228 __input: &[u8],
11229 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11230 let avail_len = __input.len();
11231 let mut payload_buf = [0; Self::ENCODED_LEN];
11232 let mut buf = if avail_len < Self::ENCODED_LEN {
11233 payload_buf[0..avail_len].copy_from_slice(__input);
11234 Bytes::new(&payload_buf)
11235 } else {
11236 Bytes::new(__input)
11237 };
11238 let mut __struct = Self::default();
11239 let tmp = buf.get_u32_le();
11240 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
11241 ::mavlink_core::error::ParserError::InvalidEnum {
11242 enum_type: "TuneFormat",
11243 value: tmp as u32,
11244 },
11245 )?;
11246 __struct.target_system = buf.get_u8();
11247 __struct.target_component = buf.get_u8();
11248 for v in &mut __struct.tune {
11249 let val = buf.get_u8();
11250 *v = val;
11251 }
11252 Ok(__struct)
11253 }
11254 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11255 let mut __tmp = BytesMut::new(bytes);
11256 #[allow(clippy::absurd_extreme_comparisons)]
11257 #[allow(unused_comparisons)]
11258 if __tmp.remaining() < Self::ENCODED_LEN {
11259 panic!(
11260 "buffer is too small (need {} bytes, but got {})",
11261 Self::ENCODED_LEN,
11262 __tmp.remaining(),
11263 )
11264 }
11265 __tmp.put_u32_le(self.format as u32);
11266 __tmp.put_u8(self.target_system);
11267 __tmp.put_u8(self.target_component);
11268 for val in &self.tune {
11269 __tmp.put_u8(*val);
11270 }
11271 if matches!(version, MavlinkVersion::V2) {
11272 let len = __tmp.len();
11273 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11274 } else {
11275 __tmp.len()
11276 }
11277 }
11278}
11279#[doc = "id: 12903"]
11280#[doc = "Data for filling the OpenDroneID Self ID message. The Self ID Message is an opportunity for the operator to (optionally) declare their identity and purpose of the flight. This message can provide additional information that could reduce the threat profile of a UA (Unmanned Aircraft) flying in a particular area or manner. This message can also be used to provide optional additional clarification in an emergency/remote ID system failure situation."]
11281#[derive(Debug, Clone, PartialEq)]
11282#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11283#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11284pub struct OPEN_DRONE_ID_SELF_ID_DATA {
11285 #[doc = "System ID (0 for broadcast)."]
11286 pub target_system: u8,
11287 #[doc = "Component ID (0 for broadcast)."]
11288 pub target_component: u8,
11289 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
11290 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11291 pub id_or_mac: [u8; 20],
11292 #[doc = "Indicates the type of the description field."]
11293 pub description_type: MavOdidDescType,
11294 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
11295 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11296 pub description: [u8; 23],
11297}
11298impl OPEN_DRONE_ID_SELF_ID_DATA {
11299 pub const ENCODED_LEN: usize = 46usize;
11300 pub const DEFAULT: Self = Self {
11301 target_system: 0_u8,
11302 target_component: 0_u8,
11303 id_or_mac: [0_u8; 20usize],
11304 description_type: MavOdidDescType::DEFAULT,
11305 description: [0_u8; 23usize],
11306 };
11307 #[cfg(feature = "arbitrary")]
11308 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11309 use arbitrary::{Arbitrary, Unstructured};
11310 let mut buf = [0u8; 1024];
11311 rng.fill_bytes(&mut buf);
11312 let mut unstructured = Unstructured::new(&buf);
11313 Self::arbitrary(&mut unstructured).unwrap_or_default()
11314 }
11315}
11316impl Default for OPEN_DRONE_ID_SELF_ID_DATA {
11317 fn default() -> Self {
11318 Self::DEFAULT.clone()
11319 }
11320}
11321impl MessageData for OPEN_DRONE_ID_SELF_ID_DATA {
11322 type Message = MavMessage;
11323 const ID: u32 = 12903u32;
11324 const NAME: &'static str = "OPEN_DRONE_ID_SELF_ID";
11325 const EXTRA_CRC: u8 = 249u8;
11326 const ENCODED_LEN: usize = 46usize;
11327 fn deser(
11328 _version: MavlinkVersion,
11329 __input: &[u8],
11330 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11331 let avail_len = __input.len();
11332 let mut payload_buf = [0; Self::ENCODED_LEN];
11333 let mut buf = if avail_len < Self::ENCODED_LEN {
11334 payload_buf[0..avail_len].copy_from_slice(__input);
11335 Bytes::new(&payload_buf)
11336 } else {
11337 Bytes::new(__input)
11338 };
11339 let mut __struct = Self::default();
11340 __struct.target_system = buf.get_u8();
11341 __struct.target_component = buf.get_u8();
11342 for v in &mut __struct.id_or_mac {
11343 let val = buf.get_u8();
11344 *v = val;
11345 }
11346 let tmp = buf.get_u8();
11347 __struct.description_type =
11348 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11349 enum_type: "MavOdidDescType",
11350 value: tmp as u32,
11351 })?;
11352 for v in &mut __struct.description {
11353 let val = buf.get_u8();
11354 *v = val;
11355 }
11356 Ok(__struct)
11357 }
11358 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11359 let mut __tmp = BytesMut::new(bytes);
11360 #[allow(clippy::absurd_extreme_comparisons)]
11361 #[allow(unused_comparisons)]
11362 if __tmp.remaining() < Self::ENCODED_LEN {
11363 panic!(
11364 "buffer is too small (need {} bytes, but got {})",
11365 Self::ENCODED_LEN,
11366 __tmp.remaining(),
11367 )
11368 }
11369 __tmp.put_u8(self.target_system);
11370 __tmp.put_u8(self.target_component);
11371 for val in &self.id_or_mac {
11372 __tmp.put_u8(*val);
11373 }
11374 __tmp.put_u8(self.description_type as u8);
11375 for val in &self.description {
11376 __tmp.put_u8(*val);
11377 }
11378 if matches!(version, MavlinkVersion::V2) {
11379 let len = __tmp.len();
11380 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11381 } else {
11382 __tmp.len()
11383 }
11384 }
11385}
11386#[doc = "id: 80"]
11387#[doc = "Cancel a long running command. The target system should respond with a COMMAND_ACK to the original command with result=MAV_RESULT_CANCELLED if the long running process was cancelled. If it has already completed, the cancel action can be ignored. The cancel action can be retried until some sort of acknowledgement to the original command has been received. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
11388#[derive(Debug, Clone, PartialEq)]
11389#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11390#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11391pub struct COMMAND_CANCEL_DATA {
11392 #[doc = "Command ID (of command to cancel)."]
11393 pub command: MavCmd,
11394 #[doc = "System executing long running command. Should not be broadcast (0)."]
11395 pub target_system: u8,
11396 #[doc = "Component executing long running command."]
11397 pub target_component: u8,
11398}
11399impl COMMAND_CANCEL_DATA {
11400 pub const ENCODED_LEN: usize = 4usize;
11401 pub const DEFAULT: Self = Self {
11402 command: MavCmd::DEFAULT,
11403 target_system: 0_u8,
11404 target_component: 0_u8,
11405 };
11406 #[cfg(feature = "arbitrary")]
11407 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11408 use arbitrary::{Arbitrary, Unstructured};
11409 let mut buf = [0u8; 1024];
11410 rng.fill_bytes(&mut buf);
11411 let mut unstructured = Unstructured::new(&buf);
11412 Self::arbitrary(&mut unstructured).unwrap_or_default()
11413 }
11414}
11415impl Default for COMMAND_CANCEL_DATA {
11416 fn default() -> Self {
11417 Self::DEFAULT.clone()
11418 }
11419}
11420impl MessageData for COMMAND_CANCEL_DATA {
11421 type Message = MavMessage;
11422 const ID: u32 = 80u32;
11423 const NAME: &'static str = "COMMAND_CANCEL";
11424 const EXTRA_CRC: u8 = 14u8;
11425 const ENCODED_LEN: usize = 4usize;
11426 fn deser(
11427 _version: MavlinkVersion,
11428 __input: &[u8],
11429 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11430 let avail_len = __input.len();
11431 let mut payload_buf = [0; Self::ENCODED_LEN];
11432 let mut buf = if avail_len < Self::ENCODED_LEN {
11433 payload_buf[0..avail_len].copy_from_slice(__input);
11434 Bytes::new(&payload_buf)
11435 } else {
11436 Bytes::new(__input)
11437 };
11438 let mut __struct = Self::default();
11439 let tmp = buf.get_u16_le();
11440 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
11441 ::mavlink_core::error::ParserError::InvalidEnum {
11442 enum_type: "MavCmd",
11443 value: tmp as u32,
11444 },
11445 )?;
11446 __struct.target_system = buf.get_u8();
11447 __struct.target_component = buf.get_u8();
11448 Ok(__struct)
11449 }
11450 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11451 let mut __tmp = BytesMut::new(bytes);
11452 #[allow(clippy::absurd_extreme_comparisons)]
11453 #[allow(unused_comparisons)]
11454 if __tmp.remaining() < Self::ENCODED_LEN {
11455 panic!(
11456 "buffer is too small (need {} bytes, but got {})",
11457 Self::ENCODED_LEN,
11458 __tmp.remaining(),
11459 )
11460 }
11461 __tmp.put_u16_le(self.command as u16);
11462 __tmp.put_u8(self.target_system);
11463 __tmp.put_u8(self.target_component);
11464 if matches!(version, MavlinkVersion::V2) {
11465 let len = __tmp.len();
11466 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11467 } else {
11468 __tmp.len()
11469 }
11470 }
11471}
11472#[doc = "id: 10007"]
11473#[doc = "Control message with all data sent in UCP control message."]
11474#[derive(Debug, Clone, PartialEq)]
11475#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11476#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11477pub struct UAVIONIX_ADSB_OUT_CONTROL_DATA {
11478 #[doc = "Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX"]
11479 pub baroAltMSL: i32,
11480 #[doc = "Mode A code (typically 1200 [0x04B0] for VFR)"]
11481 pub squawk: u16,
11482 #[doc = "ADS-B transponder control state flags"]
11483 pub state: UavionixAdsbOutControlState,
11484 #[doc = "Emergency status"]
11485 pub emergencyStatus: UavionixAdsbEmergencyStatus,
11486 #[doc = "Flight Identification: 8 ASCII characters, '0' through '9', 'A' through 'Z' or space. Spaces (0x20) used as a trailing pad character, or when call sign is unavailable."]
11487 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11488 pub flight_id: [u8; 8],
11489 #[doc = "X-Bit enable (military transponders only)"]
11490 pub x_bit: UavionixAdsbXbit,
11491}
11492impl UAVIONIX_ADSB_OUT_CONTROL_DATA {
11493 pub const ENCODED_LEN: usize = 17usize;
11494 pub const DEFAULT: Self = Self {
11495 baroAltMSL: 0_i32,
11496 squawk: 0_u16,
11497 state: UavionixAdsbOutControlState::DEFAULT,
11498 emergencyStatus: UavionixAdsbEmergencyStatus::DEFAULT,
11499 flight_id: [0_u8; 8usize],
11500 x_bit: UavionixAdsbXbit::DEFAULT,
11501 };
11502 #[cfg(feature = "arbitrary")]
11503 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11504 use arbitrary::{Arbitrary, Unstructured};
11505 let mut buf = [0u8; 1024];
11506 rng.fill_bytes(&mut buf);
11507 let mut unstructured = Unstructured::new(&buf);
11508 Self::arbitrary(&mut unstructured).unwrap_or_default()
11509 }
11510}
11511impl Default for UAVIONIX_ADSB_OUT_CONTROL_DATA {
11512 fn default() -> Self {
11513 Self::DEFAULT.clone()
11514 }
11515}
11516impl MessageData for UAVIONIX_ADSB_OUT_CONTROL_DATA {
11517 type Message = MavMessage;
11518 const ID: u32 = 10007u32;
11519 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CONTROL";
11520 const EXTRA_CRC: u8 = 71u8;
11521 const ENCODED_LEN: usize = 17usize;
11522 fn deser(
11523 _version: MavlinkVersion,
11524 __input: &[u8],
11525 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11526 let avail_len = __input.len();
11527 let mut payload_buf = [0; Self::ENCODED_LEN];
11528 let mut buf = if avail_len < Self::ENCODED_LEN {
11529 payload_buf[0..avail_len].copy_from_slice(__input);
11530 Bytes::new(&payload_buf)
11531 } else {
11532 Bytes::new(__input)
11533 };
11534 let mut __struct = Self::default();
11535 __struct.baroAltMSL = buf.get_i32_le();
11536 __struct.squawk = buf.get_u16_le();
11537 let tmp = buf.get_u8();
11538 __struct.state =
11539 UavionixAdsbOutControlState::from_bits(tmp & UavionixAdsbOutControlState::all().bits())
11540 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
11541 flag_type: "UavionixAdsbOutControlState",
11542 value: tmp as u32,
11543 })?;
11544 let tmp = buf.get_u8();
11545 __struct.emergencyStatus =
11546 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11547 enum_type: "UavionixAdsbEmergencyStatus",
11548 value: tmp as u32,
11549 })?;
11550 for v in &mut __struct.flight_id {
11551 let val = buf.get_u8();
11552 *v = val;
11553 }
11554 let tmp = buf.get_u8();
11555 __struct.x_bit = UavionixAdsbXbit::from_bits(tmp & UavionixAdsbXbit::all().bits()).ok_or(
11556 ::mavlink_core::error::ParserError::InvalidFlag {
11557 flag_type: "UavionixAdsbXbit",
11558 value: tmp as u32,
11559 },
11560 )?;
11561 Ok(__struct)
11562 }
11563 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11564 let mut __tmp = BytesMut::new(bytes);
11565 #[allow(clippy::absurd_extreme_comparisons)]
11566 #[allow(unused_comparisons)]
11567 if __tmp.remaining() < Self::ENCODED_LEN {
11568 panic!(
11569 "buffer is too small (need {} bytes, but got {})",
11570 Self::ENCODED_LEN,
11571 __tmp.remaining(),
11572 )
11573 }
11574 __tmp.put_i32_le(self.baroAltMSL);
11575 __tmp.put_u16_le(self.squawk);
11576 __tmp.put_u8(self.state.bits());
11577 __tmp.put_u8(self.emergencyStatus as u8);
11578 for val in &self.flight_id {
11579 __tmp.put_u8(*val);
11580 }
11581 __tmp.put_u8(self.x_bit.bits());
11582 if matches!(version, MavlinkVersion::V2) {
11583 let len = __tmp.len();
11584 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11585 } else {
11586 __tmp.len()
11587 }
11588 }
11589}
11590#[doc = "id: 413"]
11591#[doc = "Response to a REQUEST_EVENT in case of an error (e.g. the event is not available anymore)."]
11592#[derive(Debug, Clone, PartialEq)]
11593#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11594#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11595pub struct RESPONSE_EVENT_ERROR_DATA {
11596 #[doc = "Sequence number."]
11597 pub sequence: u16,
11598 #[doc = "Oldest Sequence number that is still available after the sequence set in REQUEST_EVENT."]
11599 pub sequence_oldest_available: u16,
11600 #[doc = "System ID"]
11601 pub target_system: u8,
11602 #[doc = "Component ID"]
11603 pub target_component: u8,
11604 #[doc = "Error reason."]
11605 pub reason: MavEventErrorReason,
11606}
11607impl RESPONSE_EVENT_ERROR_DATA {
11608 pub const ENCODED_LEN: usize = 7usize;
11609 pub const DEFAULT: Self = Self {
11610 sequence: 0_u16,
11611 sequence_oldest_available: 0_u16,
11612 target_system: 0_u8,
11613 target_component: 0_u8,
11614 reason: MavEventErrorReason::DEFAULT,
11615 };
11616 #[cfg(feature = "arbitrary")]
11617 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11618 use arbitrary::{Arbitrary, Unstructured};
11619 let mut buf = [0u8; 1024];
11620 rng.fill_bytes(&mut buf);
11621 let mut unstructured = Unstructured::new(&buf);
11622 Self::arbitrary(&mut unstructured).unwrap_or_default()
11623 }
11624}
11625impl Default for RESPONSE_EVENT_ERROR_DATA {
11626 fn default() -> Self {
11627 Self::DEFAULT.clone()
11628 }
11629}
11630impl MessageData for RESPONSE_EVENT_ERROR_DATA {
11631 type Message = MavMessage;
11632 const ID: u32 = 413u32;
11633 const NAME: &'static str = "RESPONSE_EVENT_ERROR";
11634 const EXTRA_CRC: u8 = 77u8;
11635 const ENCODED_LEN: usize = 7usize;
11636 fn deser(
11637 _version: MavlinkVersion,
11638 __input: &[u8],
11639 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11640 let avail_len = __input.len();
11641 let mut payload_buf = [0; Self::ENCODED_LEN];
11642 let mut buf = if avail_len < Self::ENCODED_LEN {
11643 payload_buf[0..avail_len].copy_from_slice(__input);
11644 Bytes::new(&payload_buf)
11645 } else {
11646 Bytes::new(__input)
11647 };
11648 let mut __struct = Self::default();
11649 __struct.sequence = buf.get_u16_le();
11650 __struct.sequence_oldest_available = buf.get_u16_le();
11651 __struct.target_system = buf.get_u8();
11652 __struct.target_component = buf.get_u8();
11653 let tmp = buf.get_u8();
11654 __struct.reason =
11655 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11656 enum_type: "MavEventErrorReason",
11657 value: tmp as u32,
11658 })?;
11659 Ok(__struct)
11660 }
11661 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11662 let mut __tmp = BytesMut::new(bytes);
11663 #[allow(clippy::absurd_extreme_comparisons)]
11664 #[allow(unused_comparisons)]
11665 if __tmp.remaining() < Self::ENCODED_LEN {
11666 panic!(
11667 "buffer is too small (need {} bytes, but got {})",
11668 Self::ENCODED_LEN,
11669 __tmp.remaining(),
11670 )
11671 }
11672 __tmp.put_u16_le(self.sequence);
11673 __tmp.put_u16_le(self.sequence_oldest_available);
11674 __tmp.put_u8(self.target_system);
11675 __tmp.put_u8(self.target_component);
11676 __tmp.put_u8(self.reason as u8);
11677 if matches!(version, MavlinkVersion::V2) {
11678 let len = __tmp.len();
11679 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11680 } else {
11681 __tmp.len()
11682 }
11683 }
11684}
11685#[doc = "id: 0"]
11686#[doc = "The heartbeat message shows that a system or component is present and responding. The type and autopilot fields (along with the message component id), allow the receiving system to treat further messages from this system appropriately (e.g. by laying out the user interface based on the autopilot). This microservice is documented at <https://mavlink.io/en/services/heartbeat.html>."]
11687#[derive(Debug, Clone, PartialEq)]
11688#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11689#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11690pub struct HEARTBEAT_DATA {
11691 #[doc = "A bitfield for use for autopilot-specific flags"]
11692 pub custom_mode: u32,
11693 #[doc = "Vehicle or component type. For a flight controller component the vehicle type (quadrotor, helicopter, etc.). For other components the component type (e.g. camera, gimbal, etc.). This should be used in preference to component id for identifying the component type."]
11694 pub mavtype: MavType,
11695 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
11696 pub autopilot: MavAutopilot,
11697 #[doc = "System mode bitmap."]
11698 pub base_mode: MavModeFlag,
11699 #[doc = "System status flag."]
11700 pub system_status: MavState,
11701 #[doc = "MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version"]
11702 pub mavlink_version: u8,
11703}
11704impl HEARTBEAT_DATA {
11705 pub const ENCODED_LEN: usize = 9usize;
11706 pub const DEFAULT: Self = Self {
11707 custom_mode: 0_u32,
11708 mavtype: MavType::DEFAULT,
11709 autopilot: MavAutopilot::DEFAULT,
11710 base_mode: MavModeFlag::DEFAULT,
11711 system_status: MavState::DEFAULT,
11712 mavlink_version: 0_u8,
11713 };
11714 #[cfg(feature = "arbitrary")]
11715 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11716 use arbitrary::{Arbitrary, Unstructured};
11717 let mut buf = [0u8; 1024];
11718 rng.fill_bytes(&mut buf);
11719 let mut unstructured = Unstructured::new(&buf);
11720 Self::arbitrary(&mut unstructured).unwrap_or_default()
11721 }
11722}
11723impl Default for HEARTBEAT_DATA {
11724 fn default() -> Self {
11725 Self::DEFAULT.clone()
11726 }
11727}
11728impl MessageData for HEARTBEAT_DATA {
11729 type Message = MavMessage;
11730 const ID: u32 = 0u32;
11731 const NAME: &'static str = "HEARTBEAT";
11732 const EXTRA_CRC: u8 = 50u8;
11733 const ENCODED_LEN: usize = 9usize;
11734 fn deser(
11735 _version: MavlinkVersion,
11736 __input: &[u8],
11737 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11738 let avail_len = __input.len();
11739 let mut payload_buf = [0; Self::ENCODED_LEN];
11740 let mut buf = if avail_len < Self::ENCODED_LEN {
11741 payload_buf[0..avail_len].copy_from_slice(__input);
11742 Bytes::new(&payload_buf)
11743 } else {
11744 Bytes::new(__input)
11745 };
11746 let mut __struct = Self::default();
11747 __struct.custom_mode = buf.get_u32_le();
11748 let tmp = buf.get_u8();
11749 __struct.mavtype =
11750 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11751 enum_type: "MavType",
11752 value: tmp as u32,
11753 })?;
11754 let tmp = buf.get_u8();
11755 __struct.autopilot =
11756 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11757 enum_type: "MavAutopilot",
11758 value: tmp as u32,
11759 })?;
11760 let tmp = buf.get_u8();
11761 __struct.base_mode = MavModeFlag::from_bits(tmp & MavModeFlag::all().bits()).ok_or(
11762 ::mavlink_core::error::ParserError::InvalidFlag {
11763 flag_type: "MavModeFlag",
11764 value: tmp as u32,
11765 },
11766 )?;
11767 let tmp = buf.get_u8();
11768 __struct.system_status =
11769 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
11770 enum_type: "MavState",
11771 value: tmp as u32,
11772 })?;
11773 __struct.mavlink_version = buf.get_u8();
11774 Ok(__struct)
11775 }
11776 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11777 let mut __tmp = BytesMut::new(bytes);
11778 #[allow(clippy::absurd_extreme_comparisons)]
11779 #[allow(unused_comparisons)]
11780 if __tmp.remaining() < Self::ENCODED_LEN {
11781 panic!(
11782 "buffer is too small (need {} bytes, but got {})",
11783 Self::ENCODED_LEN,
11784 __tmp.remaining(),
11785 )
11786 }
11787 __tmp.put_u32_le(self.custom_mode);
11788 __tmp.put_u8(self.mavtype as u8);
11789 __tmp.put_u8(self.autopilot as u8);
11790 __tmp.put_u8(self.base_mode.bits());
11791 __tmp.put_u8(self.system_status as u8);
11792 __tmp.put_u8(self.mavlink_version);
11793 if matches!(version, MavlinkVersion::V2) {
11794 let len = __tmp.len();
11795 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11796 } else {
11797 __tmp.len()
11798 }
11799 }
11800}
11801#[doc = "id: 410"]
11802#[doc = "Event message. Each new event from a particular component gets a new sequence number. The same message might be sent multiple times if (re-)requested. Most events are broadcast, some can be specific to a target component (as receivers keep track of the sequence for missed events, all events need to be broadcast. Thus we use destination_component instead of target_component)."]
11803#[derive(Debug, Clone, PartialEq)]
11804#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11805#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11806pub struct EVENT_DATA {
11807 #[doc = "Event ID (as defined in the component metadata)"]
11808 pub id: u32,
11809 #[doc = "Timestamp (time since system boot when the event happened)."]
11810 pub event_time_boot_ms: u32,
11811 #[doc = "Sequence number."]
11812 pub sequence: u16,
11813 #[doc = "Component ID"]
11814 pub destination_component: u8,
11815 #[doc = "System ID"]
11816 pub destination_system: u8,
11817 #[doc = "Log levels: 4 bits MSB: internal (for logging purposes), 4 bits LSB: external. Levels: Emergency = 0, Alert = 1, Critical = 2, Error = 3, Warning = 4, Notice = 5, Info = 6, Debug = 7, Protocol = 8, Disabled = 9"]
11818 pub log_levels: u8,
11819 #[doc = "Arguments (depend on event ID)."]
11820 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11821 pub arguments: [u8; 40],
11822}
11823impl EVENT_DATA {
11824 pub const ENCODED_LEN: usize = 53usize;
11825 pub const DEFAULT: Self = Self {
11826 id: 0_u32,
11827 event_time_boot_ms: 0_u32,
11828 sequence: 0_u16,
11829 destination_component: 0_u8,
11830 destination_system: 0_u8,
11831 log_levels: 0_u8,
11832 arguments: [0_u8; 40usize],
11833 };
11834 #[cfg(feature = "arbitrary")]
11835 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11836 use arbitrary::{Arbitrary, Unstructured};
11837 let mut buf = [0u8; 1024];
11838 rng.fill_bytes(&mut buf);
11839 let mut unstructured = Unstructured::new(&buf);
11840 Self::arbitrary(&mut unstructured).unwrap_or_default()
11841 }
11842}
11843impl Default for EVENT_DATA {
11844 fn default() -> Self {
11845 Self::DEFAULT.clone()
11846 }
11847}
11848impl MessageData for EVENT_DATA {
11849 type Message = MavMessage;
11850 const ID: u32 = 410u32;
11851 const NAME: &'static str = "EVENT";
11852 const EXTRA_CRC: u8 = 160u8;
11853 const ENCODED_LEN: usize = 53usize;
11854 fn deser(
11855 _version: MavlinkVersion,
11856 __input: &[u8],
11857 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11858 let avail_len = __input.len();
11859 let mut payload_buf = [0; Self::ENCODED_LEN];
11860 let mut buf = if avail_len < Self::ENCODED_LEN {
11861 payload_buf[0..avail_len].copy_from_slice(__input);
11862 Bytes::new(&payload_buf)
11863 } else {
11864 Bytes::new(__input)
11865 };
11866 let mut __struct = Self::default();
11867 __struct.id = buf.get_u32_le();
11868 __struct.event_time_boot_ms = buf.get_u32_le();
11869 __struct.sequence = buf.get_u16_le();
11870 __struct.destination_component = buf.get_u8();
11871 __struct.destination_system = buf.get_u8();
11872 __struct.log_levels = buf.get_u8();
11873 for v in &mut __struct.arguments {
11874 let val = buf.get_u8();
11875 *v = val;
11876 }
11877 Ok(__struct)
11878 }
11879 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11880 let mut __tmp = BytesMut::new(bytes);
11881 #[allow(clippy::absurd_extreme_comparisons)]
11882 #[allow(unused_comparisons)]
11883 if __tmp.remaining() < Self::ENCODED_LEN {
11884 panic!(
11885 "buffer is too small (need {} bytes, but got {})",
11886 Self::ENCODED_LEN,
11887 __tmp.remaining(),
11888 )
11889 }
11890 __tmp.put_u32_le(self.id);
11891 __tmp.put_u32_le(self.event_time_boot_ms);
11892 __tmp.put_u16_le(self.sequence);
11893 __tmp.put_u8(self.destination_component);
11894 __tmp.put_u8(self.destination_system);
11895 __tmp.put_u8(self.log_levels);
11896 for val in &self.arguments {
11897 __tmp.put_u8(*val);
11898 }
11899 if matches!(version, MavlinkVersion::V2) {
11900 let len = __tmp.len();
11901 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
11902 } else {
11903 __tmp.len()
11904 }
11905 }
11906}
11907#[doc = "id: 350"]
11908#[doc = "Large debug/prototyping array. The message uses the maximum available payload for data. The array_id and name fields are used to discriminate between messages in code and in user interfaces (respectively). Do not use in production code."]
11909#[derive(Debug, Clone, PartialEq)]
11910#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
11911#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
11912pub struct DEBUG_FLOAT_ARRAY_DATA {
11913 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
11914 pub time_usec: u64,
11915 #[doc = "Unique ID used to discriminate between arrays"]
11916 pub array_id: u16,
11917 #[doc = "Name, for human-friendly display in a Ground Control Station"]
11918 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11919 pub name: [u8; 10],
11920 #[doc = "data"]
11921 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
11922 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
11923 pub data: [f32; 58],
11924}
11925impl DEBUG_FLOAT_ARRAY_DATA {
11926 pub const ENCODED_LEN: usize = 252usize;
11927 pub const DEFAULT: Self = Self {
11928 time_usec: 0_u64,
11929 array_id: 0_u16,
11930 name: [0_u8; 10usize],
11931 data: [0.0_f32; 58usize],
11932 };
11933 #[cfg(feature = "arbitrary")]
11934 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
11935 use arbitrary::{Arbitrary, Unstructured};
11936 let mut buf = [0u8; 1024];
11937 rng.fill_bytes(&mut buf);
11938 let mut unstructured = Unstructured::new(&buf);
11939 Self::arbitrary(&mut unstructured).unwrap_or_default()
11940 }
11941}
11942impl Default for DEBUG_FLOAT_ARRAY_DATA {
11943 fn default() -> Self {
11944 Self::DEFAULT.clone()
11945 }
11946}
11947impl MessageData for DEBUG_FLOAT_ARRAY_DATA {
11948 type Message = MavMessage;
11949 const ID: u32 = 350u32;
11950 const NAME: &'static str = "DEBUG_FLOAT_ARRAY";
11951 const EXTRA_CRC: u8 = 232u8;
11952 const ENCODED_LEN: usize = 252usize;
11953 fn deser(
11954 _version: MavlinkVersion,
11955 __input: &[u8],
11956 ) -> Result<Self, ::mavlink_core::error::ParserError> {
11957 let avail_len = __input.len();
11958 let mut payload_buf = [0; Self::ENCODED_LEN];
11959 let mut buf = if avail_len < Self::ENCODED_LEN {
11960 payload_buf[0..avail_len].copy_from_slice(__input);
11961 Bytes::new(&payload_buf)
11962 } else {
11963 Bytes::new(__input)
11964 };
11965 let mut __struct = Self::default();
11966 __struct.time_usec = buf.get_u64_le();
11967 __struct.array_id = buf.get_u16_le();
11968 for v in &mut __struct.name {
11969 let val = buf.get_u8();
11970 *v = val;
11971 }
11972 for v in &mut __struct.data {
11973 let val = buf.get_f32_le();
11974 *v = val;
11975 }
11976 Ok(__struct)
11977 }
11978 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
11979 let mut __tmp = BytesMut::new(bytes);
11980 #[allow(clippy::absurd_extreme_comparisons)]
11981 #[allow(unused_comparisons)]
11982 if __tmp.remaining() < Self::ENCODED_LEN {
11983 panic!(
11984 "buffer is too small (need {} bytes, but got {})",
11985 Self::ENCODED_LEN,
11986 __tmp.remaining(),
11987 )
11988 }
11989 __tmp.put_u64_le(self.time_usec);
11990 __tmp.put_u16_le(self.array_id);
11991 for val in &self.name {
11992 __tmp.put_u8(*val);
11993 }
11994 for val in &self.data {
11995 __tmp.put_f32_le(*val);
11996 }
11997 if matches!(version, MavlinkVersion::V2) {
11998 let len = __tmp.len();
11999 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12000 } else {
12001 __tmp.len()
12002 }
12003 }
12004}
12005#[doc = "id: 75"]
12006#[doc = "Send a command with up to seven parameters to the MAV, where params 5 and 6 are integers and the other values are floats. This is preferred over COMMAND_LONG as it allows the MAV_FRAME to be specified for interpreting positional information, such as altitude. COMMAND_INT is also preferred when sending latitude and longitude data in params 5 and 6, as it allows for greater precision. Param 5 and 6 encode positional data as scaled integers, where the scaling depends on the actual command value. NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
12007#[derive(Debug, Clone, PartialEq)]
12008#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12009#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12010pub struct COMMAND_INT_DATA {
12011 #[doc = "PARAM1, see MAV_CMD enum"]
12012 pub param1: f32,
12013 #[doc = "PARAM2, see MAV_CMD enum"]
12014 pub param2: f32,
12015 #[doc = "PARAM3, see MAV_CMD enum"]
12016 pub param3: f32,
12017 #[doc = "PARAM4, see MAV_CMD enum"]
12018 pub param4: f32,
12019 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
12020 pub x: i32,
12021 #[doc = "PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7"]
12022 pub y: i32,
12023 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame)."]
12024 pub z: f32,
12025 #[doc = "The scheduled action for the mission item."]
12026 pub command: MavCmd,
12027 #[doc = "System ID"]
12028 pub target_system: u8,
12029 #[doc = "Component ID"]
12030 pub target_component: u8,
12031 #[doc = "The coordinate system of the COMMAND."]
12032 pub frame: MavFrame,
12033 #[doc = "Not used."]
12034 pub current: u8,
12035 #[doc = "Not used (set 0)."]
12036 pub autocontinue: u8,
12037}
12038impl COMMAND_INT_DATA {
12039 pub const ENCODED_LEN: usize = 35usize;
12040 pub const DEFAULT: Self = Self {
12041 param1: 0.0_f32,
12042 param2: 0.0_f32,
12043 param3: 0.0_f32,
12044 param4: 0.0_f32,
12045 x: 0_i32,
12046 y: 0_i32,
12047 z: 0.0_f32,
12048 command: MavCmd::DEFAULT,
12049 target_system: 0_u8,
12050 target_component: 0_u8,
12051 frame: MavFrame::DEFAULT,
12052 current: 0_u8,
12053 autocontinue: 0_u8,
12054 };
12055 #[cfg(feature = "arbitrary")]
12056 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12057 use arbitrary::{Arbitrary, Unstructured};
12058 let mut buf = [0u8; 1024];
12059 rng.fill_bytes(&mut buf);
12060 let mut unstructured = Unstructured::new(&buf);
12061 Self::arbitrary(&mut unstructured).unwrap_or_default()
12062 }
12063}
12064impl Default for COMMAND_INT_DATA {
12065 fn default() -> Self {
12066 Self::DEFAULT.clone()
12067 }
12068}
12069impl MessageData for COMMAND_INT_DATA {
12070 type Message = MavMessage;
12071 const ID: u32 = 75u32;
12072 const NAME: &'static str = "COMMAND_INT";
12073 const EXTRA_CRC: u8 = 158u8;
12074 const ENCODED_LEN: usize = 35usize;
12075 fn deser(
12076 _version: MavlinkVersion,
12077 __input: &[u8],
12078 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12079 let avail_len = __input.len();
12080 let mut payload_buf = [0; Self::ENCODED_LEN];
12081 let mut buf = if avail_len < Self::ENCODED_LEN {
12082 payload_buf[0..avail_len].copy_from_slice(__input);
12083 Bytes::new(&payload_buf)
12084 } else {
12085 Bytes::new(__input)
12086 };
12087 let mut __struct = Self::default();
12088 __struct.param1 = buf.get_f32_le();
12089 __struct.param2 = buf.get_f32_le();
12090 __struct.param3 = buf.get_f32_le();
12091 __struct.param4 = buf.get_f32_le();
12092 __struct.x = buf.get_i32_le();
12093 __struct.y = buf.get_i32_le();
12094 __struct.z = buf.get_f32_le();
12095 let tmp = buf.get_u16_le();
12096 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
12097 ::mavlink_core::error::ParserError::InvalidEnum {
12098 enum_type: "MavCmd",
12099 value: tmp as u32,
12100 },
12101 )?;
12102 __struct.target_system = buf.get_u8();
12103 __struct.target_component = buf.get_u8();
12104 let tmp = buf.get_u8();
12105 __struct.frame =
12106 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12107 enum_type: "MavFrame",
12108 value: tmp as u32,
12109 })?;
12110 __struct.current = buf.get_u8();
12111 __struct.autocontinue = buf.get_u8();
12112 Ok(__struct)
12113 }
12114 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12115 let mut __tmp = BytesMut::new(bytes);
12116 #[allow(clippy::absurd_extreme_comparisons)]
12117 #[allow(unused_comparisons)]
12118 if __tmp.remaining() < Self::ENCODED_LEN {
12119 panic!(
12120 "buffer is too small (need {} bytes, but got {})",
12121 Self::ENCODED_LEN,
12122 __tmp.remaining(),
12123 )
12124 }
12125 __tmp.put_f32_le(self.param1);
12126 __tmp.put_f32_le(self.param2);
12127 __tmp.put_f32_le(self.param3);
12128 __tmp.put_f32_le(self.param4);
12129 __tmp.put_i32_le(self.x);
12130 __tmp.put_i32_le(self.y);
12131 __tmp.put_f32_le(self.z);
12132 __tmp.put_u16_le(self.command as u16);
12133 __tmp.put_u8(self.target_system);
12134 __tmp.put_u8(self.target_component);
12135 __tmp.put_u8(self.frame as u8);
12136 __tmp.put_u8(self.current);
12137 __tmp.put_u8(self.autocontinue);
12138 if matches!(version, MavlinkVersion::V2) {
12139 let len = __tmp.len();
12140 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12141 } else {
12142 __tmp.len()
12143 }
12144 }
12145}
12146#[doc = "id: 110"]
12147#[doc = "File transfer protocol message: <https://mavlink.io/en/services/ftp.html>."]
12148#[derive(Debug, Clone, PartialEq)]
12149#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12150#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12151pub struct FILE_TRANSFER_PROTOCOL_DATA {
12152 #[doc = "Network ID (0 for broadcast)"]
12153 pub target_network: u8,
12154 #[doc = "System ID (0 for broadcast)"]
12155 pub target_system: u8,
12156 #[doc = "Component ID (0 for broadcast)"]
12157 pub target_component: u8,
12158 #[doc = "Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The content/format of this block is defined in <https://mavlink.io/en/services/ftp.html>."]
12159 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12160 pub payload: [u8; 251],
12161}
12162impl FILE_TRANSFER_PROTOCOL_DATA {
12163 pub const ENCODED_LEN: usize = 254usize;
12164 pub const DEFAULT: Self = Self {
12165 target_network: 0_u8,
12166 target_system: 0_u8,
12167 target_component: 0_u8,
12168 payload: [0_u8; 251usize],
12169 };
12170 #[cfg(feature = "arbitrary")]
12171 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12172 use arbitrary::{Arbitrary, Unstructured};
12173 let mut buf = [0u8; 1024];
12174 rng.fill_bytes(&mut buf);
12175 let mut unstructured = Unstructured::new(&buf);
12176 Self::arbitrary(&mut unstructured).unwrap_or_default()
12177 }
12178}
12179impl Default for FILE_TRANSFER_PROTOCOL_DATA {
12180 fn default() -> Self {
12181 Self::DEFAULT.clone()
12182 }
12183}
12184impl MessageData for FILE_TRANSFER_PROTOCOL_DATA {
12185 type Message = MavMessage;
12186 const ID: u32 = 110u32;
12187 const NAME: &'static str = "FILE_TRANSFER_PROTOCOL";
12188 const EXTRA_CRC: u8 = 84u8;
12189 const ENCODED_LEN: usize = 254usize;
12190 fn deser(
12191 _version: MavlinkVersion,
12192 __input: &[u8],
12193 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12194 let avail_len = __input.len();
12195 let mut payload_buf = [0; Self::ENCODED_LEN];
12196 let mut buf = if avail_len < Self::ENCODED_LEN {
12197 payload_buf[0..avail_len].copy_from_slice(__input);
12198 Bytes::new(&payload_buf)
12199 } else {
12200 Bytes::new(__input)
12201 };
12202 let mut __struct = Self::default();
12203 __struct.target_network = buf.get_u8();
12204 __struct.target_system = buf.get_u8();
12205 __struct.target_component = buf.get_u8();
12206 for v in &mut __struct.payload {
12207 let val = buf.get_u8();
12208 *v = val;
12209 }
12210 Ok(__struct)
12211 }
12212 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12213 let mut __tmp = BytesMut::new(bytes);
12214 #[allow(clippy::absurd_extreme_comparisons)]
12215 #[allow(unused_comparisons)]
12216 if __tmp.remaining() < Self::ENCODED_LEN {
12217 panic!(
12218 "buffer is too small (need {} bytes, but got {})",
12219 Self::ENCODED_LEN,
12220 __tmp.remaining(),
12221 )
12222 }
12223 __tmp.put_u8(self.target_network);
12224 __tmp.put_u8(self.target_system);
12225 __tmp.put_u8(self.target_component);
12226 for val in &self.payload {
12227 __tmp.put_u8(*val);
12228 }
12229 if matches!(version, MavlinkVersion::V2) {
12230 let len = __tmp.len();
12231 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12232 } else {
12233 __tmp.len()
12234 }
12235 }
12236}
12237#[doc = "id: 334"]
12238#[doc = "Report current used cellular network status."]
12239#[derive(Debug, Clone, PartialEq)]
12240#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12241#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12242pub struct CELLULAR_STATUS_DATA {
12243 #[doc = "Mobile country code. If unknown, set to UINT16_MAX"]
12244 pub mcc: u16,
12245 #[doc = "Mobile network code. If unknown, set to UINT16_MAX"]
12246 pub mnc: u16,
12247 #[doc = "Location area code. If unknown, set to 0"]
12248 pub lac: u16,
12249 #[doc = "Cellular modem status"]
12250 pub status: CellularStatusFlag,
12251 #[doc = "Failure reason when status in in CELLULAR_STATUS_FLAG_FAILED"]
12252 pub failure_reason: CellularNetworkFailedReason,
12253 #[doc = "Cellular network radio type: gsm, cdma, lte..."]
12254 pub mavtype: CellularNetworkRadioType,
12255 #[doc = "Signal quality in percent. If unknown, set to UINT8_MAX"]
12256 pub quality: u8,
12257}
12258impl CELLULAR_STATUS_DATA {
12259 pub const ENCODED_LEN: usize = 10usize;
12260 pub const DEFAULT: Self = Self {
12261 mcc: 0_u16,
12262 mnc: 0_u16,
12263 lac: 0_u16,
12264 status: CellularStatusFlag::DEFAULT,
12265 failure_reason: CellularNetworkFailedReason::DEFAULT,
12266 mavtype: CellularNetworkRadioType::DEFAULT,
12267 quality: 0_u8,
12268 };
12269 #[cfg(feature = "arbitrary")]
12270 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12271 use arbitrary::{Arbitrary, Unstructured};
12272 let mut buf = [0u8; 1024];
12273 rng.fill_bytes(&mut buf);
12274 let mut unstructured = Unstructured::new(&buf);
12275 Self::arbitrary(&mut unstructured).unwrap_or_default()
12276 }
12277}
12278impl Default for CELLULAR_STATUS_DATA {
12279 fn default() -> Self {
12280 Self::DEFAULT.clone()
12281 }
12282}
12283impl MessageData for CELLULAR_STATUS_DATA {
12284 type Message = MavMessage;
12285 const ID: u32 = 334u32;
12286 const NAME: &'static str = "CELLULAR_STATUS";
12287 const EXTRA_CRC: u8 = 72u8;
12288 const ENCODED_LEN: usize = 10usize;
12289 fn deser(
12290 _version: MavlinkVersion,
12291 __input: &[u8],
12292 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12293 let avail_len = __input.len();
12294 let mut payload_buf = [0; Self::ENCODED_LEN];
12295 let mut buf = if avail_len < Self::ENCODED_LEN {
12296 payload_buf[0..avail_len].copy_from_slice(__input);
12297 Bytes::new(&payload_buf)
12298 } else {
12299 Bytes::new(__input)
12300 };
12301 let mut __struct = Self::default();
12302 __struct.mcc = buf.get_u16_le();
12303 __struct.mnc = buf.get_u16_le();
12304 __struct.lac = buf.get_u16_le();
12305 let tmp = buf.get_u8();
12306 __struct.status =
12307 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12308 enum_type: "CellularStatusFlag",
12309 value: tmp as u32,
12310 })?;
12311 let tmp = buf.get_u8();
12312 __struct.failure_reason =
12313 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12314 enum_type: "CellularNetworkFailedReason",
12315 value: tmp as u32,
12316 })?;
12317 let tmp = buf.get_u8();
12318 __struct.mavtype =
12319 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
12320 enum_type: "CellularNetworkRadioType",
12321 value: tmp as u32,
12322 })?;
12323 __struct.quality = buf.get_u8();
12324 Ok(__struct)
12325 }
12326 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12327 let mut __tmp = BytesMut::new(bytes);
12328 #[allow(clippy::absurd_extreme_comparisons)]
12329 #[allow(unused_comparisons)]
12330 if __tmp.remaining() < Self::ENCODED_LEN {
12331 panic!(
12332 "buffer is too small (need {} bytes, but got {})",
12333 Self::ENCODED_LEN,
12334 __tmp.remaining(),
12335 )
12336 }
12337 __tmp.put_u16_le(self.mcc);
12338 __tmp.put_u16_le(self.mnc);
12339 __tmp.put_u16_le(self.lac);
12340 __tmp.put_u8(self.status as u8);
12341 __tmp.put_u8(self.failure_reason as u8);
12342 __tmp.put_u8(self.mavtype as u8);
12343 __tmp.put_u8(self.quality);
12344 if matches!(version, MavlinkVersion::V2) {
12345 let len = __tmp.len();
12346 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12347 } else {
12348 __tmp.len()
12349 }
12350 }
12351}
12352#[doc = "id: 66"]
12353#[doc = "Request a data stream."]
12354#[derive(Debug, Clone, PartialEq)]
12355#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12356#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12357pub struct REQUEST_DATA_STREAM_DATA {
12358 #[doc = "The requested message rate"]
12359 pub req_message_rate: u16,
12360 #[doc = "The target requested to send the message stream."]
12361 pub target_system: u8,
12362 #[doc = "The target requested to send the message stream."]
12363 pub target_component: u8,
12364 #[doc = "The ID of the requested data stream"]
12365 pub req_stream_id: u8,
12366 #[doc = "1 to start sending, 0 to stop sending."]
12367 pub start_stop: u8,
12368}
12369impl REQUEST_DATA_STREAM_DATA {
12370 pub const ENCODED_LEN: usize = 6usize;
12371 pub const DEFAULT: Self = Self {
12372 req_message_rate: 0_u16,
12373 target_system: 0_u8,
12374 target_component: 0_u8,
12375 req_stream_id: 0_u8,
12376 start_stop: 0_u8,
12377 };
12378 #[cfg(feature = "arbitrary")]
12379 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12380 use arbitrary::{Arbitrary, Unstructured};
12381 let mut buf = [0u8; 1024];
12382 rng.fill_bytes(&mut buf);
12383 let mut unstructured = Unstructured::new(&buf);
12384 Self::arbitrary(&mut unstructured).unwrap_or_default()
12385 }
12386}
12387impl Default for REQUEST_DATA_STREAM_DATA {
12388 fn default() -> Self {
12389 Self::DEFAULT.clone()
12390 }
12391}
12392impl MessageData for REQUEST_DATA_STREAM_DATA {
12393 type Message = MavMessage;
12394 const ID: u32 = 66u32;
12395 const NAME: &'static str = "REQUEST_DATA_STREAM";
12396 const EXTRA_CRC: u8 = 148u8;
12397 const ENCODED_LEN: usize = 6usize;
12398 fn deser(
12399 _version: MavlinkVersion,
12400 __input: &[u8],
12401 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12402 let avail_len = __input.len();
12403 let mut payload_buf = [0; Self::ENCODED_LEN];
12404 let mut buf = if avail_len < Self::ENCODED_LEN {
12405 payload_buf[0..avail_len].copy_from_slice(__input);
12406 Bytes::new(&payload_buf)
12407 } else {
12408 Bytes::new(__input)
12409 };
12410 let mut __struct = Self::default();
12411 __struct.req_message_rate = buf.get_u16_le();
12412 __struct.target_system = buf.get_u8();
12413 __struct.target_component = buf.get_u8();
12414 __struct.req_stream_id = buf.get_u8();
12415 __struct.start_stop = buf.get_u8();
12416 Ok(__struct)
12417 }
12418 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12419 let mut __tmp = BytesMut::new(bytes);
12420 #[allow(clippy::absurd_extreme_comparisons)]
12421 #[allow(unused_comparisons)]
12422 if __tmp.remaining() < Self::ENCODED_LEN {
12423 panic!(
12424 "buffer is too small (need {} bytes, but got {})",
12425 Self::ENCODED_LEN,
12426 __tmp.remaining(),
12427 )
12428 }
12429 __tmp.put_u16_le(self.req_message_rate);
12430 __tmp.put_u8(self.target_system);
12431 __tmp.put_u8(self.target_component);
12432 __tmp.put_u8(self.req_stream_id);
12433 __tmp.put_u8(self.start_stop);
12434 if matches!(version, MavlinkVersion::V2) {
12435 let len = __tmp.len();
12436 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12437 } else {
12438 __tmp.len()
12439 }
12440 }
12441}
12442#[doc = "id: 321"]
12443#[doc = "Request all parameters of this component. All parameters should be emitted in response as PARAM_EXT_VALUE."]
12444#[derive(Debug, Clone, PartialEq)]
12445#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12446#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12447pub struct PARAM_EXT_REQUEST_LIST_DATA {
12448 #[doc = "System ID"]
12449 pub target_system: u8,
12450 #[doc = "Component ID"]
12451 pub target_component: u8,
12452}
12453impl PARAM_EXT_REQUEST_LIST_DATA {
12454 pub const ENCODED_LEN: usize = 2usize;
12455 pub const DEFAULT: Self = Self {
12456 target_system: 0_u8,
12457 target_component: 0_u8,
12458 };
12459 #[cfg(feature = "arbitrary")]
12460 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12461 use arbitrary::{Arbitrary, Unstructured};
12462 let mut buf = [0u8; 1024];
12463 rng.fill_bytes(&mut buf);
12464 let mut unstructured = Unstructured::new(&buf);
12465 Self::arbitrary(&mut unstructured).unwrap_or_default()
12466 }
12467}
12468impl Default for PARAM_EXT_REQUEST_LIST_DATA {
12469 fn default() -> Self {
12470 Self::DEFAULT.clone()
12471 }
12472}
12473impl MessageData for PARAM_EXT_REQUEST_LIST_DATA {
12474 type Message = MavMessage;
12475 const ID: u32 = 321u32;
12476 const NAME: &'static str = "PARAM_EXT_REQUEST_LIST";
12477 const EXTRA_CRC: u8 = 88u8;
12478 const ENCODED_LEN: usize = 2usize;
12479 fn deser(
12480 _version: MavlinkVersion,
12481 __input: &[u8],
12482 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12483 let avail_len = __input.len();
12484 let mut payload_buf = [0; Self::ENCODED_LEN];
12485 let mut buf = if avail_len < Self::ENCODED_LEN {
12486 payload_buf[0..avail_len].copy_from_slice(__input);
12487 Bytes::new(&payload_buf)
12488 } else {
12489 Bytes::new(__input)
12490 };
12491 let mut __struct = Self::default();
12492 __struct.target_system = buf.get_u8();
12493 __struct.target_component = buf.get_u8();
12494 Ok(__struct)
12495 }
12496 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12497 let mut __tmp = BytesMut::new(bytes);
12498 #[allow(clippy::absurd_extreme_comparisons)]
12499 #[allow(unused_comparisons)]
12500 if __tmp.remaining() < Self::ENCODED_LEN {
12501 panic!(
12502 "buffer is too small (need {} bytes, but got {})",
12503 Self::ENCODED_LEN,
12504 __tmp.remaining(),
12505 )
12506 }
12507 __tmp.put_u8(self.target_system);
12508 __tmp.put_u8(self.target_component);
12509 if matches!(version, MavlinkVersion::V2) {
12510 let len = __tmp.len();
12511 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12512 } else {
12513 __tmp.len()
12514 }
12515 }
12516}
12517#[doc = "id: 231"]
12518#[doc = "Wind estimate from vehicle. Note that despite the name, this message does not actually contain any covariances but instead variability and accuracy fields in terms of standard deviation (1-STD)."]
12519#[derive(Debug, Clone, PartialEq)]
12520#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12521#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12522pub struct WIND_COV_DATA {
12523 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
12524 pub time_usec: u64,
12525 #[doc = "Wind in North (NED) direction (NAN if unknown)"]
12526 pub wind_x: f32,
12527 #[doc = "Wind in East (NED) direction (NAN if unknown)"]
12528 pub wind_y: f32,
12529 #[doc = "Wind in down (NED) direction (NAN if unknown)"]
12530 pub wind_z: f32,
12531 #[doc = "Variability of wind in XY, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
12532 pub var_horiz: f32,
12533 #[doc = "Variability of wind in Z, 1-STD estimated from a 1 Hz lowpassed wind estimate (NAN if unknown)"]
12534 pub var_vert: f32,
12535 #[doc = "Altitude (MSL) that this measurement was taken at (NAN if unknown)"]
12536 pub wind_alt: f32,
12537 #[doc = "Horizontal speed 1-STD accuracy (0 if unknown)"]
12538 pub horiz_accuracy: f32,
12539 #[doc = "Vertical speed 1-STD accuracy (0 if unknown)"]
12540 pub vert_accuracy: f32,
12541}
12542impl WIND_COV_DATA {
12543 pub const ENCODED_LEN: usize = 40usize;
12544 pub const DEFAULT: Self = Self {
12545 time_usec: 0_u64,
12546 wind_x: 0.0_f32,
12547 wind_y: 0.0_f32,
12548 wind_z: 0.0_f32,
12549 var_horiz: 0.0_f32,
12550 var_vert: 0.0_f32,
12551 wind_alt: 0.0_f32,
12552 horiz_accuracy: 0.0_f32,
12553 vert_accuracy: 0.0_f32,
12554 };
12555 #[cfg(feature = "arbitrary")]
12556 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12557 use arbitrary::{Arbitrary, Unstructured};
12558 let mut buf = [0u8; 1024];
12559 rng.fill_bytes(&mut buf);
12560 let mut unstructured = Unstructured::new(&buf);
12561 Self::arbitrary(&mut unstructured).unwrap_or_default()
12562 }
12563}
12564impl Default for WIND_COV_DATA {
12565 fn default() -> Self {
12566 Self::DEFAULT.clone()
12567 }
12568}
12569impl MessageData for WIND_COV_DATA {
12570 type Message = MavMessage;
12571 const ID: u32 = 231u32;
12572 const NAME: &'static str = "WIND_COV";
12573 const EXTRA_CRC: u8 = 105u8;
12574 const ENCODED_LEN: usize = 40usize;
12575 fn deser(
12576 _version: MavlinkVersion,
12577 __input: &[u8],
12578 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12579 let avail_len = __input.len();
12580 let mut payload_buf = [0; Self::ENCODED_LEN];
12581 let mut buf = if avail_len < Self::ENCODED_LEN {
12582 payload_buf[0..avail_len].copy_from_slice(__input);
12583 Bytes::new(&payload_buf)
12584 } else {
12585 Bytes::new(__input)
12586 };
12587 let mut __struct = Self::default();
12588 __struct.time_usec = buf.get_u64_le();
12589 __struct.wind_x = buf.get_f32_le();
12590 __struct.wind_y = buf.get_f32_le();
12591 __struct.wind_z = buf.get_f32_le();
12592 __struct.var_horiz = buf.get_f32_le();
12593 __struct.var_vert = buf.get_f32_le();
12594 __struct.wind_alt = buf.get_f32_le();
12595 __struct.horiz_accuracy = buf.get_f32_le();
12596 __struct.vert_accuracy = buf.get_f32_le();
12597 Ok(__struct)
12598 }
12599 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12600 let mut __tmp = BytesMut::new(bytes);
12601 #[allow(clippy::absurd_extreme_comparisons)]
12602 #[allow(unused_comparisons)]
12603 if __tmp.remaining() < Self::ENCODED_LEN {
12604 panic!(
12605 "buffer is too small (need {} bytes, but got {})",
12606 Self::ENCODED_LEN,
12607 __tmp.remaining(),
12608 )
12609 }
12610 __tmp.put_u64_le(self.time_usec);
12611 __tmp.put_f32_le(self.wind_x);
12612 __tmp.put_f32_le(self.wind_y);
12613 __tmp.put_f32_le(self.wind_z);
12614 __tmp.put_f32_le(self.var_horiz);
12615 __tmp.put_f32_le(self.var_vert);
12616 __tmp.put_f32_le(self.wind_alt);
12617 __tmp.put_f32_le(self.horiz_accuracy);
12618 __tmp.put_f32_le(self.vert_accuracy);
12619 if matches!(version, MavlinkVersion::V2) {
12620 let len = __tmp.len();
12621 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12622 } else {
12623 __tmp.len()
12624 }
12625 }
12626}
12627#[doc = "id: 30"]
12628#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, Y-right, X-front, ZYX, intrinsic)."]
12629#[derive(Debug, Clone, PartialEq)]
12630#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12631#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12632pub struct ATTITUDE_DATA {
12633 #[doc = "Timestamp (time since system boot)."]
12634 pub time_boot_ms: u32,
12635 #[doc = "Roll angle (-pi..+pi)"]
12636 pub roll: f32,
12637 #[doc = "Pitch angle (-pi..+pi)"]
12638 pub pitch: f32,
12639 #[doc = "Yaw angle (-pi..+pi)"]
12640 pub yaw: f32,
12641 #[doc = "Roll angular speed"]
12642 pub rollspeed: f32,
12643 #[doc = "Pitch angular speed"]
12644 pub pitchspeed: f32,
12645 #[doc = "Yaw angular speed"]
12646 pub yawspeed: f32,
12647}
12648impl ATTITUDE_DATA {
12649 pub const ENCODED_LEN: usize = 28usize;
12650 pub const DEFAULT: Self = Self {
12651 time_boot_ms: 0_u32,
12652 roll: 0.0_f32,
12653 pitch: 0.0_f32,
12654 yaw: 0.0_f32,
12655 rollspeed: 0.0_f32,
12656 pitchspeed: 0.0_f32,
12657 yawspeed: 0.0_f32,
12658 };
12659 #[cfg(feature = "arbitrary")]
12660 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12661 use arbitrary::{Arbitrary, Unstructured};
12662 let mut buf = [0u8; 1024];
12663 rng.fill_bytes(&mut buf);
12664 let mut unstructured = Unstructured::new(&buf);
12665 Self::arbitrary(&mut unstructured).unwrap_or_default()
12666 }
12667}
12668impl Default for ATTITUDE_DATA {
12669 fn default() -> Self {
12670 Self::DEFAULT.clone()
12671 }
12672}
12673impl MessageData for ATTITUDE_DATA {
12674 type Message = MavMessage;
12675 const ID: u32 = 30u32;
12676 const NAME: &'static str = "ATTITUDE";
12677 const EXTRA_CRC: u8 = 39u8;
12678 const ENCODED_LEN: usize = 28usize;
12679 fn deser(
12680 _version: MavlinkVersion,
12681 __input: &[u8],
12682 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12683 let avail_len = __input.len();
12684 let mut payload_buf = [0; Self::ENCODED_LEN];
12685 let mut buf = if avail_len < Self::ENCODED_LEN {
12686 payload_buf[0..avail_len].copy_from_slice(__input);
12687 Bytes::new(&payload_buf)
12688 } else {
12689 Bytes::new(__input)
12690 };
12691 let mut __struct = Self::default();
12692 __struct.time_boot_ms = buf.get_u32_le();
12693 __struct.roll = buf.get_f32_le();
12694 __struct.pitch = buf.get_f32_le();
12695 __struct.yaw = buf.get_f32_le();
12696 __struct.rollspeed = buf.get_f32_le();
12697 __struct.pitchspeed = buf.get_f32_le();
12698 __struct.yawspeed = buf.get_f32_le();
12699 Ok(__struct)
12700 }
12701 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12702 let mut __tmp = BytesMut::new(bytes);
12703 #[allow(clippy::absurd_extreme_comparisons)]
12704 #[allow(unused_comparisons)]
12705 if __tmp.remaining() < Self::ENCODED_LEN {
12706 panic!(
12707 "buffer is too small (need {} bytes, but got {})",
12708 Self::ENCODED_LEN,
12709 __tmp.remaining(),
12710 )
12711 }
12712 __tmp.put_u32_le(self.time_boot_ms);
12713 __tmp.put_f32_le(self.roll);
12714 __tmp.put_f32_le(self.pitch);
12715 __tmp.put_f32_le(self.yaw);
12716 __tmp.put_f32_le(self.rollspeed);
12717 __tmp.put_f32_le(self.pitchspeed);
12718 __tmp.put_f32_le(self.yawspeed);
12719 if matches!(version, MavlinkVersion::V2) {
12720 let len = __tmp.len();
12721 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12722 } else {
12723 __tmp.len()
12724 }
12725 }
12726}
12727#[doc = "id: 109"]
12728#[doc = "Status generated by radio and injected into MAVLink stream."]
12729#[derive(Debug, Clone, PartialEq)]
12730#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12731#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12732pub struct RADIO_STATUS_DATA {
12733 #[doc = "Count of radio packet receive errors (since boot)."]
12734 pub rxerrors: u16,
12735 #[doc = "Count of error corrected radio packets (since boot)."]
12736 pub fixed: u16,
12737 #[doc = "Local (message sender) received signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
12738 pub rssi: u8,
12739 #[doc = "Remote (message receiver) signal strength indication in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
12740 pub remrssi: u8,
12741 #[doc = "Remaining free transmitter buffer space."]
12742 pub txbuf: u8,
12743 #[doc = "Local background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
12744 pub noise: u8,
12745 #[doc = "Remote background noise level. These are device dependent RSSI values (scale as approx 2x dB on SiK radios). Values: [0-254], UINT8_MAX: invalid/unknown."]
12746 pub remnoise: u8,
12747}
12748impl RADIO_STATUS_DATA {
12749 pub const ENCODED_LEN: usize = 9usize;
12750 pub const DEFAULT: Self = Self {
12751 rxerrors: 0_u16,
12752 fixed: 0_u16,
12753 rssi: 0_u8,
12754 remrssi: 0_u8,
12755 txbuf: 0_u8,
12756 noise: 0_u8,
12757 remnoise: 0_u8,
12758 };
12759 #[cfg(feature = "arbitrary")]
12760 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12761 use arbitrary::{Arbitrary, Unstructured};
12762 let mut buf = [0u8; 1024];
12763 rng.fill_bytes(&mut buf);
12764 let mut unstructured = Unstructured::new(&buf);
12765 Self::arbitrary(&mut unstructured).unwrap_or_default()
12766 }
12767}
12768impl Default for RADIO_STATUS_DATA {
12769 fn default() -> Self {
12770 Self::DEFAULT.clone()
12771 }
12772}
12773impl MessageData for RADIO_STATUS_DATA {
12774 type Message = MavMessage;
12775 const ID: u32 = 109u32;
12776 const NAME: &'static str = "RADIO_STATUS";
12777 const EXTRA_CRC: u8 = 185u8;
12778 const ENCODED_LEN: usize = 9usize;
12779 fn deser(
12780 _version: MavlinkVersion,
12781 __input: &[u8],
12782 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12783 let avail_len = __input.len();
12784 let mut payload_buf = [0; Self::ENCODED_LEN];
12785 let mut buf = if avail_len < Self::ENCODED_LEN {
12786 payload_buf[0..avail_len].copy_from_slice(__input);
12787 Bytes::new(&payload_buf)
12788 } else {
12789 Bytes::new(__input)
12790 };
12791 let mut __struct = Self::default();
12792 __struct.rxerrors = buf.get_u16_le();
12793 __struct.fixed = buf.get_u16_le();
12794 __struct.rssi = buf.get_u8();
12795 __struct.remrssi = buf.get_u8();
12796 __struct.txbuf = buf.get_u8();
12797 __struct.noise = buf.get_u8();
12798 __struct.remnoise = buf.get_u8();
12799 Ok(__struct)
12800 }
12801 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12802 let mut __tmp = BytesMut::new(bytes);
12803 #[allow(clippy::absurd_extreme_comparisons)]
12804 #[allow(unused_comparisons)]
12805 if __tmp.remaining() < Self::ENCODED_LEN {
12806 panic!(
12807 "buffer is too small (need {} bytes, but got {})",
12808 Self::ENCODED_LEN,
12809 __tmp.remaining(),
12810 )
12811 }
12812 __tmp.put_u16_le(self.rxerrors);
12813 __tmp.put_u16_le(self.fixed);
12814 __tmp.put_u8(self.rssi);
12815 __tmp.put_u8(self.remrssi);
12816 __tmp.put_u8(self.txbuf);
12817 __tmp.put_u8(self.noise);
12818 __tmp.put_u8(self.remnoise);
12819 if matches!(version, MavlinkVersion::V2) {
12820 let len = __tmp.len();
12821 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12822 } else {
12823 __tmp.len()
12824 }
12825 }
12826}
12827#[doc = "id: 251"]
12828#[doc = "Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
12829#[derive(Debug, Clone, PartialEq)]
12830#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12831#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12832pub struct NAMED_VALUE_FLOAT_DATA {
12833 #[doc = "Timestamp (time since system boot)."]
12834 pub time_boot_ms: u32,
12835 #[doc = "Floating point value"]
12836 pub value: f32,
12837 #[doc = "Name of the debug variable"]
12838 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
12839 pub name: [u8; 10],
12840}
12841impl NAMED_VALUE_FLOAT_DATA {
12842 pub const ENCODED_LEN: usize = 18usize;
12843 pub const DEFAULT: Self = Self {
12844 time_boot_ms: 0_u32,
12845 value: 0.0_f32,
12846 name: [0_u8; 10usize],
12847 };
12848 #[cfg(feature = "arbitrary")]
12849 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12850 use arbitrary::{Arbitrary, Unstructured};
12851 let mut buf = [0u8; 1024];
12852 rng.fill_bytes(&mut buf);
12853 let mut unstructured = Unstructured::new(&buf);
12854 Self::arbitrary(&mut unstructured).unwrap_or_default()
12855 }
12856}
12857impl Default for NAMED_VALUE_FLOAT_DATA {
12858 fn default() -> Self {
12859 Self::DEFAULT.clone()
12860 }
12861}
12862impl MessageData for NAMED_VALUE_FLOAT_DATA {
12863 type Message = MavMessage;
12864 const ID: u32 = 251u32;
12865 const NAME: &'static str = "NAMED_VALUE_FLOAT";
12866 const EXTRA_CRC: u8 = 170u8;
12867 const ENCODED_LEN: usize = 18usize;
12868 fn deser(
12869 _version: MavlinkVersion,
12870 __input: &[u8],
12871 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12872 let avail_len = __input.len();
12873 let mut payload_buf = [0; Self::ENCODED_LEN];
12874 let mut buf = if avail_len < Self::ENCODED_LEN {
12875 payload_buf[0..avail_len].copy_from_slice(__input);
12876 Bytes::new(&payload_buf)
12877 } else {
12878 Bytes::new(__input)
12879 };
12880 let mut __struct = Self::default();
12881 __struct.time_boot_ms = buf.get_u32_le();
12882 __struct.value = buf.get_f32_le();
12883 for v in &mut __struct.name {
12884 let val = buf.get_u8();
12885 *v = val;
12886 }
12887 Ok(__struct)
12888 }
12889 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12890 let mut __tmp = BytesMut::new(bytes);
12891 #[allow(clippy::absurd_extreme_comparisons)]
12892 #[allow(unused_comparisons)]
12893 if __tmp.remaining() < Self::ENCODED_LEN {
12894 panic!(
12895 "buffer is too small (need {} bytes, but got {})",
12896 Self::ENCODED_LEN,
12897 __tmp.remaining(),
12898 )
12899 }
12900 __tmp.put_u32_le(self.time_boot_ms);
12901 __tmp.put_f32_le(self.value);
12902 for val in &self.name {
12903 __tmp.put_u8(*val);
12904 }
12905 if matches!(version, MavlinkVersion::V2) {
12906 let len = __tmp.len();
12907 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12908 } else {
12909 __tmp.len()
12910 }
12911 }
12912}
12913#[doc = "id: 49"]
12914#[doc = "Publishes the GPS coordinates of the vehicle local origin (0,0,0) position. Emitted whenever a new GPS-Local position mapping is requested or set - e.g. following SET_GPS_GLOBAL_ORIGIN message."]
12915#[derive(Debug, Clone, PartialEq)]
12916#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
12917#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
12918pub struct GPS_GLOBAL_ORIGIN_DATA {
12919 #[doc = "Latitude (WGS84)"]
12920 pub latitude: i32,
12921 #[doc = "Longitude (WGS84)"]
12922 pub longitude: i32,
12923 #[doc = "Altitude (MSL). Positive for up."]
12924 pub altitude: i32,
12925 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
12926 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
12927 pub time_usec: u64,
12928}
12929impl GPS_GLOBAL_ORIGIN_DATA {
12930 pub const ENCODED_LEN: usize = 20usize;
12931 pub const DEFAULT: Self = Self {
12932 latitude: 0_i32,
12933 longitude: 0_i32,
12934 altitude: 0_i32,
12935 time_usec: 0_u64,
12936 };
12937 #[cfg(feature = "arbitrary")]
12938 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
12939 use arbitrary::{Arbitrary, Unstructured};
12940 let mut buf = [0u8; 1024];
12941 rng.fill_bytes(&mut buf);
12942 let mut unstructured = Unstructured::new(&buf);
12943 Self::arbitrary(&mut unstructured).unwrap_or_default()
12944 }
12945}
12946impl Default for GPS_GLOBAL_ORIGIN_DATA {
12947 fn default() -> Self {
12948 Self::DEFAULT.clone()
12949 }
12950}
12951impl MessageData for GPS_GLOBAL_ORIGIN_DATA {
12952 type Message = MavMessage;
12953 const ID: u32 = 49u32;
12954 const NAME: &'static str = "GPS_GLOBAL_ORIGIN";
12955 const EXTRA_CRC: u8 = 39u8;
12956 const ENCODED_LEN: usize = 20usize;
12957 fn deser(
12958 _version: MavlinkVersion,
12959 __input: &[u8],
12960 ) -> Result<Self, ::mavlink_core::error::ParserError> {
12961 let avail_len = __input.len();
12962 let mut payload_buf = [0; Self::ENCODED_LEN];
12963 let mut buf = if avail_len < Self::ENCODED_LEN {
12964 payload_buf[0..avail_len].copy_from_slice(__input);
12965 Bytes::new(&payload_buf)
12966 } else {
12967 Bytes::new(__input)
12968 };
12969 let mut __struct = Self::default();
12970 __struct.latitude = buf.get_i32_le();
12971 __struct.longitude = buf.get_i32_le();
12972 __struct.altitude = buf.get_i32_le();
12973 __struct.time_usec = buf.get_u64_le();
12974 Ok(__struct)
12975 }
12976 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
12977 let mut __tmp = BytesMut::new(bytes);
12978 #[allow(clippy::absurd_extreme_comparisons)]
12979 #[allow(unused_comparisons)]
12980 if __tmp.remaining() < Self::ENCODED_LEN {
12981 panic!(
12982 "buffer is too small (need {} bytes, but got {})",
12983 Self::ENCODED_LEN,
12984 __tmp.remaining(),
12985 )
12986 }
12987 __tmp.put_i32_le(self.latitude);
12988 __tmp.put_i32_le(self.longitude);
12989 __tmp.put_i32_le(self.altitude);
12990 __tmp.put_u64_le(self.time_usec);
12991 if matches!(version, MavlinkVersion::V2) {
12992 let len = __tmp.len();
12993 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
12994 } else {
12995 __tmp.len()
12996 }
12997 }
12998}
12999#[doc = "id: 87"]
13000#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_GLOBAL_INT if the vehicle is being controlled this way."]
13001#[derive(Debug, Clone, PartialEq)]
13002#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13003#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13004pub struct POSITION_TARGET_GLOBAL_INT_DATA {
13005 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
13006 pub time_boot_ms: u32,
13007 #[doc = "Latitude in WGS84 frame"]
13008 pub lat_int: i32,
13009 #[doc = "Longitude in WGS84 frame"]
13010 pub lon_int: i32,
13011 #[doc = "Altitude (MSL, AGL or relative to home altitude, depending on frame)"]
13012 pub alt: f32,
13013 #[doc = "X velocity in NED frame"]
13014 pub vx: f32,
13015 #[doc = "Y velocity in NED frame"]
13016 pub vy: f32,
13017 #[doc = "Z velocity in NED frame"]
13018 pub vz: f32,
13019 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
13020 pub afx: f32,
13021 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
13022 pub afy: f32,
13023 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
13024 pub afz: f32,
13025 #[doc = "yaw setpoint"]
13026 pub yaw: f32,
13027 #[doc = "yaw rate setpoint"]
13028 pub yaw_rate: f32,
13029 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
13030 pub type_mask: PositionTargetTypemask,
13031 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
13032 pub coordinate_frame: MavFrame,
13033}
13034impl POSITION_TARGET_GLOBAL_INT_DATA {
13035 pub const ENCODED_LEN: usize = 51usize;
13036 pub const DEFAULT: Self = Self {
13037 time_boot_ms: 0_u32,
13038 lat_int: 0_i32,
13039 lon_int: 0_i32,
13040 alt: 0.0_f32,
13041 vx: 0.0_f32,
13042 vy: 0.0_f32,
13043 vz: 0.0_f32,
13044 afx: 0.0_f32,
13045 afy: 0.0_f32,
13046 afz: 0.0_f32,
13047 yaw: 0.0_f32,
13048 yaw_rate: 0.0_f32,
13049 type_mask: PositionTargetTypemask::DEFAULT,
13050 coordinate_frame: MavFrame::DEFAULT,
13051 };
13052 #[cfg(feature = "arbitrary")]
13053 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13054 use arbitrary::{Arbitrary, Unstructured};
13055 let mut buf = [0u8; 1024];
13056 rng.fill_bytes(&mut buf);
13057 let mut unstructured = Unstructured::new(&buf);
13058 Self::arbitrary(&mut unstructured).unwrap_or_default()
13059 }
13060}
13061impl Default for POSITION_TARGET_GLOBAL_INT_DATA {
13062 fn default() -> Self {
13063 Self::DEFAULT.clone()
13064 }
13065}
13066impl MessageData for POSITION_TARGET_GLOBAL_INT_DATA {
13067 type Message = MavMessage;
13068 const ID: u32 = 87u32;
13069 const NAME: &'static str = "POSITION_TARGET_GLOBAL_INT";
13070 const EXTRA_CRC: u8 = 150u8;
13071 const ENCODED_LEN: usize = 51usize;
13072 fn deser(
13073 _version: MavlinkVersion,
13074 __input: &[u8],
13075 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13076 let avail_len = __input.len();
13077 let mut payload_buf = [0; Self::ENCODED_LEN];
13078 let mut buf = if avail_len < Self::ENCODED_LEN {
13079 payload_buf[0..avail_len].copy_from_slice(__input);
13080 Bytes::new(&payload_buf)
13081 } else {
13082 Bytes::new(__input)
13083 };
13084 let mut __struct = Self::default();
13085 __struct.time_boot_ms = buf.get_u32_le();
13086 __struct.lat_int = buf.get_i32_le();
13087 __struct.lon_int = buf.get_i32_le();
13088 __struct.alt = buf.get_f32_le();
13089 __struct.vx = buf.get_f32_le();
13090 __struct.vy = buf.get_f32_le();
13091 __struct.vz = buf.get_f32_le();
13092 __struct.afx = buf.get_f32_le();
13093 __struct.afy = buf.get_f32_le();
13094 __struct.afz = buf.get_f32_le();
13095 __struct.yaw = buf.get_f32_le();
13096 __struct.yaw_rate = buf.get_f32_le();
13097 let tmp = buf.get_u16_le();
13098 __struct.type_mask = PositionTargetTypemask::from_bits(
13099 tmp & PositionTargetTypemask::all().bits(),
13100 )
13101 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
13102 flag_type: "PositionTargetTypemask",
13103 value: tmp as u32,
13104 })?;
13105 let tmp = buf.get_u8();
13106 __struct.coordinate_frame =
13107 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13108 enum_type: "MavFrame",
13109 value: tmp as u32,
13110 })?;
13111 Ok(__struct)
13112 }
13113 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13114 let mut __tmp = BytesMut::new(bytes);
13115 #[allow(clippy::absurd_extreme_comparisons)]
13116 #[allow(unused_comparisons)]
13117 if __tmp.remaining() < Self::ENCODED_LEN {
13118 panic!(
13119 "buffer is too small (need {} bytes, but got {})",
13120 Self::ENCODED_LEN,
13121 __tmp.remaining(),
13122 )
13123 }
13124 __tmp.put_u32_le(self.time_boot_ms);
13125 __tmp.put_i32_le(self.lat_int);
13126 __tmp.put_i32_le(self.lon_int);
13127 __tmp.put_f32_le(self.alt);
13128 __tmp.put_f32_le(self.vx);
13129 __tmp.put_f32_le(self.vy);
13130 __tmp.put_f32_le(self.vz);
13131 __tmp.put_f32_le(self.afx);
13132 __tmp.put_f32_le(self.afy);
13133 __tmp.put_f32_le(self.afz);
13134 __tmp.put_f32_le(self.yaw);
13135 __tmp.put_f32_le(self.yaw_rate);
13136 __tmp.put_u16_le(self.type_mask.bits());
13137 __tmp.put_u8(self.coordinate_frame as u8);
13138 if matches!(version, MavlinkVersion::V2) {
13139 let len = __tmp.len();
13140 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13141 } else {
13142 __tmp.len()
13143 }
13144 }
13145}
13146#[doc = "id: 25"]
13147#[doc = "The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION_INT for the global position estimate. This message can contain information for up to 20 satellites."]
13148#[derive(Debug, Clone, PartialEq)]
13149#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13150#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13151pub struct GPS_STATUS_DATA {
13152 #[doc = "Number of satellites visible"]
13153 pub satellites_visible: u8,
13154 #[doc = "Global satellite ID"]
13155 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13156 pub satellite_prn: [u8; 20],
13157 #[doc = "0: Satellite not used, 1: used for localization"]
13158 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13159 pub satellite_used: [u8; 20],
13160 #[doc = "Elevation (0: right on top of receiver, 90: on the horizon) of satellite"]
13161 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13162 pub satellite_elevation: [u8; 20],
13163 #[doc = "Direction of satellite, 0: 0 deg, 255: 360 deg."]
13164 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13165 pub satellite_azimuth: [u8; 20],
13166 #[doc = "Signal to noise ratio of satellite"]
13167 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13168 pub satellite_snr: [u8; 20],
13169}
13170impl GPS_STATUS_DATA {
13171 pub const ENCODED_LEN: usize = 101usize;
13172 pub const DEFAULT: Self = Self {
13173 satellites_visible: 0_u8,
13174 satellite_prn: [0_u8; 20usize],
13175 satellite_used: [0_u8; 20usize],
13176 satellite_elevation: [0_u8; 20usize],
13177 satellite_azimuth: [0_u8; 20usize],
13178 satellite_snr: [0_u8; 20usize],
13179 };
13180 #[cfg(feature = "arbitrary")]
13181 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13182 use arbitrary::{Arbitrary, Unstructured};
13183 let mut buf = [0u8; 1024];
13184 rng.fill_bytes(&mut buf);
13185 let mut unstructured = Unstructured::new(&buf);
13186 Self::arbitrary(&mut unstructured).unwrap_or_default()
13187 }
13188}
13189impl Default for GPS_STATUS_DATA {
13190 fn default() -> Self {
13191 Self::DEFAULT.clone()
13192 }
13193}
13194impl MessageData for GPS_STATUS_DATA {
13195 type Message = MavMessage;
13196 const ID: u32 = 25u32;
13197 const NAME: &'static str = "GPS_STATUS";
13198 const EXTRA_CRC: u8 = 23u8;
13199 const ENCODED_LEN: usize = 101usize;
13200 fn deser(
13201 _version: MavlinkVersion,
13202 __input: &[u8],
13203 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13204 let avail_len = __input.len();
13205 let mut payload_buf = [0; Self::ENCODED_LEN];
13206 let mut buf = if avail_len < Self::ENCODED_LEN {
13207 payload_buf[0..avail_len].copy_from_slice(__input);
13208 Bytes::new(&payload_buf)
13209 } else {
13210 Bytes::new(__input)
13211 };
13212 let mut __struct = Self::default();
13213 __struct.satellites_visible = buf.get_u8();
13214 for v in &mut __struct.satellite_prn {
13215 let val = buf.get_u8();
13216 *v = val;
13217 }
13218 for v in &mut __struct.satellite_used {
13219 let val = buf.get_u8();
13220 *v = val;
13221 }
13222 for v in &mut __struct.satellite_elevation {
13223 let val = buf.get_u8();
13224 *v = val;
13225 }
13226 for v in &mut __struct.satellite_azimuth {
13227 let val = buf.get_u8();
13228 *v = val;
13229 }
13230 for v in &mut __struct.satellite_snr {
13231 let val = buf.get_u8();
13232 *v = val;
13233 }
13234 Ok(__struct)
13235 }
13236 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13237 let mut __tmp = BytesMut::new(bytes);
13238 #[allow(clippy::absurd_extreme_comparisons)]
13239 #[allow(unused_comparisons)]
13240 if __tmp.remaining() < Self::ENCODED_LEN {
13241 panic!(
13242 "buffer is too small (need {} bytes, but got {})",
13243 Self::ENCODED_LEN,
13244 __tmp.remaining(),
13245 )
13246 }
13247 __tmp.put_u8(self.satellites_visible);
13248 for val in &self.satellite_prn {
13249 __tmp.put_u8(*val);
13250 }
13251 for val in &self.satellite_used {
13252 __tmp.put_u8(*val);
13253 }
13254 for val in &self.satellite_elevation {
13255 __tmp.put_u8(*val);
13256 }
13257 for val in &self.satellite_azimuth {
13258 __tmp.put_u8(*val);
13259 }
13260 for val in &self.satellite_snr {
13261 __tmp.put_u8(*val);
13262 }
13263 if matches!(version, MavlinkVersion::V2) {
13264 let len = __tmp.len();
13265 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13266 } else {
13267 __tmp.len()
13268 }
13269 }
13270}
13271#[doc = "id: 21"]
13272#[doc = "Request all parameters of this component. After this request, all parameters are emitted. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
13273#[derive(Debug, Clone, PartialEq)]
13274#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13275#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13276pub struct PARAM_REQUEST_LIST_DATA {
13277 #[doc = "System ID"]
13278 pub target_system: u8,
13279 #[doc = "Component ID"]
13280 pub target_component: u8,
13281}
13282impl PARAM_REQUEST_LIST_DATA {
13283 pub const ENCODED_LEN: usize = 2usize;
13284 pub const DEFAULT: Self = Self {
13285 target_system: 0_u8,
13286 target_component: 0_u8,
13287 };
13288 #[cfg(feature = "arbitrary")]
13289 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13290 use arbitrary::{Arbitrary, Unstructured};
13291 let mut buf = [0u8; 1024];
13292 rng.fill_bytes(&mut buf);
13293 let mut unstructured = Unstructured::new(&buf);
13294 Self::arbitrary(&mut unstructured).unwrap_or_default()
13295 }
13296}
13297impl Default for PARAM_REQUEST_LIST_DATA {
13298 fn default() -> Self {
13299 Self::DEFAULT.clone()
13300 }
13301}
13302impl MessageData for PARAM_REQUEST_LIST_DATA {
13303 type Message = MavMessage;
13304 const ID: u32 = 21u32;
13305 const NAME: &'static str = "PARAM_REQUEST_LIST";
13306 const EXTRA_CRC: u8 = 159u8;
13307 const ENCODED_LEN: usize = 2usize;
13308 fn deser(
13309 _version: MavlinkVersion,
13310 __input: &[u8],
13311 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13312 let avail_len = __input.len();
13313 let mut payload_buf = [0; Self::ENCODED_LEN];
13314 let mut buf = if avail_len < Self::ENCODED_LEN {
13315 payload_buf[0..avail_len].copy_from_slice(__input);
13316 Bytes::new(&payload_buf)
13317 } else {
13318 Bytes::new(__input)
13319 };
13320 let mut __struct = Self::default();
13321 __struct.target_system = buf.get_u8();
13322 __struct.target_component = buf.get_u8();
13323 Ok(__struct)
13324 }
13325 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13326 let mut __tmp = BytesMut::new(bytes);
13327 #[allow(clippy::absurd_extreme_comparisons)]
13328 #[allow(unused_comparisons)]
13329 if __tmp.remaining() < Self::ENCODED_LEN {
13330 panic!(
13331 "buffer is too small (need {} bytes, but got {})",
13332 Self::ENCODED_LEN,
13333 __tmp.remaining(),
13334 )
13335 }
13336 __tmp.put_u8(self.target_system);
13337 __tmp.put_u8(self.target_component);
13338 if matches!(version, MavlinkVersion::V2) {
13339 let len = __tmp.len();
13340 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13341 } else {
13342 __tmp.len()
13343 }
13344 }
13345}
13346#[doc = "id: 12919"]
13347#[doc = "Update the data in the OPEN_DRONE_ID_SYSTEM message with new location information. This can be sent to update the location information for the operator when no other information in the SYSTEM message has changed. This message allows for efficient operation on radio links which have limited uplink bandwidth while meeting requirements for update frequency of the operator location."]
13348#[derive(Debug, Clone, PartialEq)]
13349#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13350#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13351pub struct OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
13352 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
13353 pub operator_latitude: i32,
13354 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
13355 pub operator_longitude: i32,
13356 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
13357 pub operator_altitude_geo: f32,
13358 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
13359 pub timestamp: u32,
13360 #[doc = "System ID (0 for broadcast)."]
13361 pub target_system: u8,
13362 #[doc = "Component ID (0 for broadcast)."]
13363 pub target_component: u8,
13364}
13365impl OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
13366 pub const ENCODED_LEN: usize = 18usize;
13367 pub const DEFAULT: Self = Self {
13368 operator_latitude: 0_i32,
13369 operator_longitude: 0_i32,
13370 operator_altitude_geo: 0.0_f32,
13371 timestamp: 0_u32,
13372 target_system: 0_u8,
13373 target_component: 0_u8,
13374 };
13375 #[cfg(feature = "arbitrary")]
13376 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13377 use arbitrary::{Arbitrary, Unstructured};
13378 let mut buf = [0u8; 1024];
13379 rng.fill_bytes(&mut buf);
13380 let mut unstructured = Unstructured::new(&buf);
13381 Self::arbitrary(&mut unstructured).unwrap_or_default()
13382 }
13383}
13384impl Default for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
13385 fn default() -> Self {
13386 Self::DEFAULT.clone()
13387 }
13388}
13389impl MessageData for OPEN_DRONE_ID_SYSTEM_UPDATE_DATA {
13390 type Message = MavMessage;
13391 const ID: u32 = 12919u32;
13392 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM_UPDATE";
13393 const EXTRA_CRC: u8 = 7u8;
13394 const ENCODED_LEN: usize = 18usize;
13395 fn deser(
13396 _version: MavlinkVersion,
13397 __input: &[u8],
13398 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13399 let avail_len = __input.len();
13400 let mut payload_buf = [0; Self::ENCODED_LEN];
13401 let mut buf = if avail_len < Self::ENCODED_LEN {
13402 payload_buf[0..avail_len].copy_from_slice(__input);
13403 Bytes::new(&payload_buf)
13404 } else {
13405 Bytes::new(__input)
13406 };
13407 let mut __struct = Self::default();
13408 __struct.operator_latitude = buf.get_i32_le();
13409 __struct.operator_longitude = buf.get_i32_le();
13410 __struct.operator_altitude_geo = buf.get_f32_le();
13411 __struct.timestamp = buf.get_u32_le();
13412 __struct.target_system = buf.get_u8();
13413 __struct.target_component = buf.get_u8();
13414 Ok(__struct)
13415 }
13416 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13417 let mut __tmp = BytesMut::new(bytes);
13418 #[allow(clippy::absurd_extreme_comparisons)]
13419 #[allow(unused_comparisons)]
13420 if __tmp.remaining() < Self::ENCODED_LEN {
13421 panic!(
13422 "buffer is too small (need {} bytes, but got {})",
13423 Self::ENCODED_LEN,
13424 __tmp.remaining(),
13425 )
13426 }
13427 __tmp.put_i32_le(self.operator_latitude);
13428 __tmp.put_i32_le(self.operator_longitude);
13429 __tmp.put_f32_le(self.operator_altitude_geo);
13430 __tmp.put_u32_le(self.timestamp);
13431 __tmp.put_u8(self.target_system);
13432 __tmp.put_u8(self.target_component);
13433 if matches!(version, MavlinkVersion::V2) {
13434 let len = __tmp.len();
13435 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13436 } else {
13437 __tmp.len()
13438 }
13439 }
13440}
13441#[doc = "id: 371"]
13442#[doc = "Fuel status. This message provides \"generic\" fuel level information for in a GCS and for triggering failsafes in an autopilot. The fuel type and associated units for fields in this message are defined in the enum MAV_FUEL_TYPE. The reported `consumed_fuel` and `remaining_fuel` must only be supplied if measured: they must not be inferred from the `maximum_fuel` and the other value. A recipient can assume that if these fields are supplied they are accurate. If not provided, the recipient can infer `remaining_fuel` from `maximum_fuel` and `consumed_fuel` on the assumption that the fuel was initially at its maximum (this is what battery monitors assume). Note however that this is an assumption, and the UI should prompt the user appropriately (i.e. notify user that they should fill the tank before boot). This kind of information may also be sent in fuel-specific messages such as BATTERY_STATUS_V2. If both messages are sent for the same fuel system, the ids and corresponding information must match. This should be streamed (nominally at 0.1 Hz)."]
13443#[derive(Debug, Clone, PartialEq)]
13444#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13445#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13446pub struct FUEL_STATUS_DATA {
13447 #[doc = "Capacity when full. Must be provided."]
13448 pub maximum_fuel: f32,
13449 #[doc = "Consumed fuel (measured). This value should not be inferred: if not measured set to NaN. NaN: field not provided."]
13450 pub consumed_fuel: f32,
13451 #[doc = "Remaining fuel until empty (measured). The value should not be inferred: if not measured set to NaN. NaN: field not provided."]
13452 pub remaining_fuel: f32,
13453 #[doc = "Positive value when emptying/using, and negative if filling/replacing. NaN: field not provided."]
13454 pub flow_rate: f32,
13455 #[doc = "Fuel temperature. NaN: field not provided."]
13456 pub temperature: f32,
13457 #[doc = "Fuel type. Defines units for fuel capacity and consumption fields above."]
13458 pub fuel_type: MavFuelType,
13459 #[doc = "Fuel ID. Must match ID of other messages for same fuel system, such as BATTERY_STATUS_V2."]
13460 pub id: u8,
13461 #[doc = "Percentage of remaining fuel, relative to full. Values: [0-100], UINT8_MAX: field not provided."]
13462 pub percent_remaining: u8,
13463}
13464impl FUEL_STATUS_DATA {
13465 pub const ENCODED_LEN: usize = 26usize;
13466 pub const DEFAULT: Self = Self {
13467 maximum_fuel: 0.0_f32,
13468 consumed_fuel: 0.0_f32,
13469 remaining_fuel: 0.0_f32,
13470 flow_rate: 0.0_f32,
13471 temperature: 0.0_f32,
13472 fuel_type: MavFuelType::DEFAULT,
13473 id: 0_u8,
13474 percent_remaining: 0_u8,
13475 };
13476 #[cfg(feature = "arbitrary")]
13477 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13478 use arbitrary::{Arbitrary, Unstructured};
13479 let mut buf = [0u8; 1024];
13480 rng.fill_bytes(&mut buf);
13481 let mut unstructured = Unstructured::new(&buf);
13482 Self::arbitrary(&mut unstructured).unwrap_or_default()
13483 }
13484}
13485impl Default for FUEL_STATUS_DATA {
13486 fn default() -> Self {
13487 Self::DEFAULT.clone()
13488 }
13489}
13490impl MessageData for FUEL_STATUS_DATA {
13491 type Message = MavMessage;
13492 const ID: u32 = 371u32;
13493 const NAME: &'static str = "FUEL_STATUS";
13494 const EXTRA_CRC: u8 = 10u8;
13495 const ENCODED_LEN: usize = 26usize;
13496 fn deser(
13497 _version: MavlinkVersion,
13498 __input: &[u8],
13499 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13500 let avail_len = __input.len();
13501 let mut payload_buf = [0; Self::ENCODED_LEN];
13502 let mut buf = if avail_len < Self::ENCODED_LEN {
13503 payload_buf[0..avail_len].copy_from_slice(__input);
13504 Bytes::new(&payload_buf)
13505 } else {
13506 Bytes::new(__input)
13507 };
13508 let mut __struct = Self::default();
13509 __struct.maximum_fuel = buf.get_f32_le();
13510 __struct.consumed_fuel = buf.get_f32_le();
13511 __struct.remaining_fuel = buf.get_f32_le();
13512 __struct.flow_rate = buf.get_f32_le();
13513 __struct.temperature = buf.get_f32_le();
13514 let tmp = buf.get_u32_le();
13515 __struct.fuel_type = FromPrimitive::from_u32(tmp).ok_or(
13516 ::mavlink_core::error::ParserError::InvalidEnum {
13517 enum_type: "MavFuelType",
13518 value: tmp as u32,
13519 },
13520 )?;
13521 __struct.id = buf.get_u8();
13522 __struct.percent_remaining = buf.get_u8();
13523 Ok(__struct)
13524 }
13525 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13526 let mut __tmp = BytesMut::new(bytes);
13527 #[allow(clippy::absurd_extreme_comparisons)]
13528 #[allow(unused_comparisons)]
13529 if __tmp.remaining() < Self::ENCODED_LEN {
13530 panic!(
13531 "buffer is too small (need {} bytes, but got {})",
13532 Self::ENCODED_LEN,
13533 __tmp.remaining(),
13534 )
13535 }
13536 __tmp.put_f32_le(self.maximum_fuel);
13537 __tmp.put_f32_le(self.consumed_fuel);
13538 __tmp.put_f32_le(self.remaining_fuel);
13539 __tmp.put_f32_le(self.flow_rate);
13540 __tmp.put_f32_le(self.temperature);
13541 __tmp.put_u32_le(self.fuel_type as u32);
13542 __tmp.put_u8(self.id);
13543 __tmp.put_u8(self.percent_remaining);
13544 if matches!(version, MavlinkVersion::V2) {
13545 let len = __tmp.len();
13546 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13547 } else {
13548 __tmp.len()
13549 }
13550 }
13551}
13552#[doc = "id: 249"]
13553#[doc = "Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
13554#[derive(Debug, Clone, PartialEq)]
13555#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13556#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13557pub struct MEMORY_VECT_DATA {
13558 #[doc = "Starting address of the debug variables"]
13559 pub address: u16,
13560 #[doc = "Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below"]
13561 pub ver: u8,
13562 #[doc = "Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14"]
13563 pub mavtype: u8,
13564 #[doc = "Memory contents at specified address"]
13565 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
13566 pub value: [i8; 32],
13567}
13568impl MEMORY_VECT_DATA {
13569 pub const ENCODED_LEN: usize = 36usize;
13570 pub const DEFAULT: Self = Self {
13571 address: 0_u16,
13572 ver: 0_u8,
13573 mavtype: 0_u8,
13574 value: [0_i8; 32usize],
13575 };
13576 #[cfg(feature = "arbitrary")]
13577 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13578 use arbitrary::{Arbitrary, Unstructured};
13579 let mut buf = [0u8; 1024];
13580 rng.fill_bytes(&mut buf);
13581 let mut unstructured = Unstructured::new(&buf);
13582 Self::arbitrary(&mut unstructured).unwrap_or_default()
13583 }
13584}
13585impl Default for MEMORY_VECT_DATA {
13586 fn default() -> Self {
13587 Self::DEFAULT.clone()
13588 }
13589}
13590impl MessageData for MEMORY_VECT_DATA {
13591 type Message = MavMessage;
13592 const ID: u32 = 249u32;
13593 const NAME: &'static str = "MEMORY_VECT";
13594 const EXTRA_CRC: u8 = 204u8;
13595 const ENCODED_LEN: usize = 36usize;
13596 fn deser(
13597 _version: MavlinkVersion,
13598 __input: &[u8],
13599 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13600 let avail_len = __input.len();
13601 let mut payload_buf = [0; Self::ENCODED_LEN];
13602 let mut buf = if avail_len < Self::ENCODED_LEN {
13603 payload_buf[0..avail_len].copy_from_slice(__input);
13604 Bytes::new(&payload_buf)
13605 } else {
13606 Bytes::new(__input)
13607 };
13608 let mut __struct = Self::default();
13609 __struct.address = buf.get_u16_le();
13610 __struct.ver = buf.get_u8();
13611 __struct.mavtype = buf.get_u8();
13612 for v in &mut __struct.value {
13613 let val = buf.get_i8();
13614 *v = val;
13615 }
13616 Ok(__struct)
13617 }
13618 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13619 let mut __tmp = BytesMut::new(bytes);
13620 #[allow(clippy::absurd_extreme_comparisons)]
13621 #[allow(unused_comparisons)]
13622 if __tmp.remaining() < Self::ENCODED_LEN {
13623 panic!(
13624 "buffer is too small (need {} bytes, but got {})",
13625 Self::ENCODED_LEN,
13626 __tmp.remaining(),
13627 )
13628 }
13629 __tmp.put_u16_le(self.address);
13630 __tmp.put_u8(self.ver);
13631 __tmp.put_u8(self.mavtype);
13632 for val in &self.value {
13633 __tmp.put_i8(*val);
13634 }
13635 if matches!(version, MavlinkVersion::V2) {
13636 let len = __tmp.len();
13637 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13638 } else {
13639 __tmp.len()
13640 }
13641 }
13642}
13643#[doc = "id: 10002"]
13644#[doc = "Dynamic data used to generate ADS-B out transponder data (send at 5Hz)."]
13645#[derive(Debug, Clone, PartialEq)]
13646#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13647#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13648pub struct UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
13649 #[doc = "UTC time in seconds since GPS epoch (Jan 6, 1980). If unknown set to UINT32_MAX"]
13650 pub utcTime: u32,
13651 #[doc = "Latitude WGS84 (deg * 1E7). If unknown set to INT32_MAX"]
13652 pub gpsLat: i32,
13653 #[doc = "Longitude WGS84 (deg * 1E7). If unknown set to INT32_MAX"]
13654 pub gpsLon: i32,
13655 #[doc = "Altitude (WGS84). UP +ve. If unknown set to INT32_MAX"]
13656 pub gpsAlt: i32,
13657 #[doc = "Barometric pressure altitude (MSL) relative to a standard atmosphere of 1013.2 mBar and NOT bar corrected altitude (m * 1E-3). (up +ve). If unknown set to INT32_MAX"]
13658 pub baroAltMSL: i32,
13659 #[doc = "Horizontal accuracy in mm (m * 1E-3). If unknown set to UINT32_MAX"]
13660 pub accuracyHor: u32,
13661 #[doc = "Vertical accuracy in cm. If unknown set to UINT16_MAX"]
13662 pub accuracyVert: u16,
13663 #[doc = "Velocity accuracy in mm/s (m * 1E-3). If unknown set to UINT16_MAX"]
13664 pub accuracyVel: u16,
13665 #[doc = "GPS vertical speed in cm/s. If unknown set to INT16_MAX"]
13666 pub velVert: i16,
13667 #[doc = "North-South velocity over ground in cm/s North +ve. If unknown set to INT16_MAX"]
13668 pub velNS: i16,
13669 #[doc = "East-West velocity over ground in cm/s East +ve. If unknown set to INT16_MAX"]
13670 pub VelEW: i16,
13671 #[doc = "ADS-B transponder dynamic input state flags"]
13672 pub state: UavionixAdsbOutDynamicState,
13673 #[doc = "Mode A code (typically 1200 [0x04B0] for VFR)"]
13674 pub squawk: u16,
13675 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK"]
13676 pub gpsFix: UavionixAdsbOutDynamicGpsFix,
13677 #[doc = "Number of satellites visible. If unknown set to UINT8_MAX"]
13678 pub numSats: u8,
13679 #[doc = "Emergency status"]
13680 pub emergencyStatus: UavionixAdsbEmergencyStatus,
13681}
13682impl UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
13683 pub const ENCODED_LEN: usize = 41usize;
13684 pub const DEFAULT: Self = Self {
13685 utcTime: 0_u32,
13686 gpsLat: 0_i32,
13687 gpsLon: 0_i32,
13688 gpsAlt: 0_i32,
13689 baroAltMSL: 0_i32,
13690 accuracyHor: 0_u32,
13691 accuracyVert: 0_u16,
13692 accuracyVel: 0_u16,
13693 velVert: 0_i16,
13694 velNS: 0_i16,
13695 VelEW: 0_i16,
13696 state: UavionixAdsbOutDynamicState::DEFAULT,
13697 squawk: 0_u16,
13698 gpsFix: UavionixAdsbOutDynamicGpsFix::DEFAULT,
13699 numSats: 0_u8,
13700 emergencyStatus: UavionixAdsbEmergencyStatus::DEFAULT,
13701 };
13702 #[cfg(feature = "arbitrary")]
13703 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13704 use arbitrary::{Arbitrary, Unstructured};
13705 let mut buf = [0u8; 1024];
13706 rng.fill_bytes(&mut buf);
13707 let mut unstructured = Unstructured::new(&buf);
13708 Self::arbitrary(&mut unstructured).unwrap_or_default()
13709 }
13710}
13711impl Default for UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
13712 fn default() -> Self {
13713 Self::DEFAULT.clone()
13714 }
13715}
13716impl MessageData for UAVIONIX_ADSB_OUT_DYNAMIC_DATA {
13717 type Message = MavMessage;
13718 const ID: u32 = 10002u32;
13719 const NAME: &'static str = "UAVIONIX_ADSB_OUT_DYNAMIC";
13720 const EXTRA_CRC: u8 = 186u8;
13721 const ENCODED_LEN: usize = 41usize;
13722 fn deser(
13723 _version: MavlinkVersion,
13724 __input: &[u8],
13725 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13726 let avail_len = __input.len();
13727 let mut payload_buf = [0; Self::ENCODED_LEN];
13728 let mut buf = if avail_len < Self::ENCODED_LEN {
13729 payload_buf[0..avail_len].copy_from_slice(__input);
13730 Bytes::new(&payload_buf)
13731 } else {
13732 Bytes::new(__input)
13733 };
13734 let mut __struct = Self::default();
13735 __struct.utcTime = buf.get_u32_le();
13736 __struct.gpsLat = buf.get_i32_le();
13737 __struct.gpsLon = buf.get_i32_le();
13738 __struct.gpsAlt = buf.get_i32_le();
13739 __struct.baroAltMSL = buf.get_i32_le();
13740 __struct.accuracyHor = buf.get_u32_le();
13741 __struct.accuracyVert = buf.get_u16_le();
13742 __struct.accuracyVel = buf.get_u16_le();
13743 __struct.velVert = buf.get_i16_le();
13744 __struct.velNS = buf.get_i16_le();
13745 __struct.VelEW = buf.get_i16_le();
13746 let tmp = buf.get_u16_le();
13747 __struct.state =
13748 UavionixAdsbOutDynamicState::from_bits(tmp & UavionixAdsbOutDynamicState::all().bits())
13749 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
13750 flag_type: "UavionixAdsbOutDynamicState",
13751 value: tmp as u32,
13752 })?;
13753 __struct.squawk = buf.get_u16_le();
13754 let tmp = buf.get_u8();
13755 __struct.gpsFix =
13756 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13757 enum_type: "UavionixAdsbOutDynamicGpsFix",
13758 value: tmp as u32,
13759 })?;
13760 __struct.numSats = buf.get_u8();
13761 let tmp = buf.get_u8();
13762 __struct.emergencyStatus =
13763 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13764 enum_type: "UavionixAdsbEmergencyStatus",
13765 value: tmp as u32,
13766 })?;
13767 Ok(__struct)
13768 }
13769 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13770 let mut __tmp = BytesMut::new(bytes);
13771 #[allow(clippy::absurd_extreme_comparisons)]
13772 #[allow(unused_comparisons)]
13773 if __tmp.remaining() < Self::ENCODED_LEN {
13774 panic!(
13775 "buffer is too small (need {} bytes, but got {})",
13776 Self::ENCODED_LEN,
13777 __tmp.remaining(),
13778 )
13779 }
13780 __tmp.put_u32_le(self.utcTime);
13781 __tmp.put_i32_le(self.gpsLat);
13782 __tmp.put_i32_le(self.gpsLon);
13783 __tmp.put_i32_le(self.gpsAlt);
13784 __tmp.put_i32_le(self.baroAltMSL);
13785 __tmp.put_u32_le(self.accuracyHor);
13786 __tmp.put_u16_le(self.accuracyVert);
13787 __tmp.put_u16_le(self.accuracyVel);
13788 __tmp.put_i16_le(self.velVert);
13789 __tmp.put_i16_le(self.velNS);
13790 __tmp.put_i16_le(self.VelEW);
13791 __tmp.put_u16_le(self.state.bits());
13792 __tmp.put_u16_le(self.squawk);
13793 __tmp.put_u8(self.gpsFix as u8);
13794 __tmp.put_u8(self.numSats);
13795 __tmp.put_u8(self.emergencyStatus as u8);
13796 if matches!(version, MavlinkVersion::V2) {
13797 let len = __tmp.len();
13798 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13799 } else {
13800 __tmp.len()
13801 }
13802 }
13803}
13804#[doc = "id: 260"]
13805#[doc = "Settings of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
13806#[derive(Debug, Clone, PartialEq)]
13807#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13808#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13809pub struct CAMERA_SETTINGS_DATA {
13810 #[doc = "Timestamp (time since system boot)."]
13811 pub time_boot_ms: u32,
13812 #[doc = "Camera mode"]
13813 pub mode_id: CameraMode,
13814 #[doc = "Current zoom level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
13815 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13816 pub zoomLevel: f32,
13817 #[doc = "Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known)"]
13818 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13819 pub focusLevel: f32,
13820 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
13821 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13822 pub camera_device_id: u8,
13823}
13824impl CAMERA_SETTINGS_DATA {
13825 pub const ENCODED_LEN: usize = 14usize;
13826 pub const DEFAULT: Self = Self {
13827 time_boot_ms: 0_u32,
13828 mode_id: CameraMode::DEFAULT,
13829 zoomLevel: 0.0_f32,
13830 focusLevel: 0.0_f32,
13831 camera_device_id: 0_u8,
13832 };
13833 #[cfg(feature = "arbitrary")]
13834 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13835 use arbitrary::{Arbitrary, Unstructured};
13836 let mut buf = [0u8; 1024];
13837 rng.fill_bytes(&mut buf);
13838 let mut unstructured = Unstructured::new(&buf);
13839 Self::arbitrary(&mut unstructured).unwrap_or_default()
13840 }
13841}
13842impl Default for CAMERA_SETTINGS_DATA {
13843 fn default() -> Self {
13844 Self::DEFAULT.clone()
13845 }
13846}
13847impl MessageData for CAMERA_SETTINGS_DATA {
13848 type Message = MavMessage;
13849 const ID: u32 = 260u32;
13850 const NAME: &'static str = "CAMERA_SETTINGS";
13851 const EXTRA_CRC: u8 = 146u8;
13852 const ENCODED_LEN: usize = 14usize;
13853 fn deser(
13854 _version: MavlinkVersion,
13855 __input: &[u8],
13856 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13857 let avail_len = __input.len();
13858 let mut payload_buf = [0; Self::ENCODED_LEN];
13859 let mut buf = if avail_len < Self::ENCODED_LEN {
13860 payload_buf[0..avail_len].copy_from_slice(__input);
13861 Bytes::new(&payload_buf)
13862 } else {
13863 Bytes::new(__input)
13864 };
13865 let mut __struct = Self::default();
13866 __struct.time_boot_ms = buf.get_u32_le();
13867 let tmp = buf.get_u8();
13868 __struct.mode_id =
13869 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
13870 enum_type: "CameraMode",
13871 value: tmp as u32,
13872 })?;
13873 __struct.zoomLevel = buf.get_f32_le();
13874 __struct.focusLevel = buf.get_f32_le();
13875 __struct.camera_device_id = buf.get_u8();
13876 Ok(__struct)
13877 }
13878 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
13879 let mut __tmp = BytesMut::new(bytes);
13880 #[allow(clippy::absurd_extreme_comparisons)]
13881 #[allow(unused_comparisons)]
13882 if __tmp.remaining() < Self::ENCODED_LEN {
13883 panic!(
13884 "buffer is too small (need {} bytes, but got {})",
13885 Self::ENCODED_LEN,
13886 __tmp.remaining(),
13887 )
13888 }
13889 __tmp.put_u32_le(self.time_boot_ms);
13890 __tmp.put_u8(self.mode_id as u8);
13891 __tmp.put_f32_le(self.zoomLevel);
13892 __tmp.put_f32_le(self.focusLevel);
13893 __tmp.put_u8(self.camera_device_id);
13894 if matches!(version, MavlinkVersion::V2) {
13895 let len = __tmp.len();
13896 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
13897 } else {
13898 __tmp.len()
13899 }
13900 }
13901}
13902#[doc = "id: 36"]
13903#[doc = "Superseded by ACTUATOR_OUTPUT_STATUS. The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%."]
13904#[derive(Debug, Clone, PartialEq)]
13905#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
13906#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
13907pub struct SERVO_OUTPUT_RAW_DATA {
13908 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
13909 pub time_usec: u32,
13910 #[doc = "Servo output 1 value"]
13911 pub servo1_raw: u16,
13912 #[doc = "Servo output 2 value"]
13913 pub servo2_raw: u16,
13914 #[doc = "Servo output 3 value"]
13915 pub servo3_raw: u16,
13916 #[doc = "Servo output 4 value"]
13917 pub servo4_raw: u16,
13918 #[doc = "Servo output 5 value"]
13919 pub servo5_raw: u16,
13920 #[doc = "Servo output 6 value"]
13921 pub servo6_raw: u16,
13922 #[doc = "Servo output 7 value"]
13923 pub servo7_raw: u16,
13924 #[doc = "Servo output 8 value"]
13925 pub servo8_raw: u16,
13926 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
13927 pub port: u8,
13928 #[doc = "Servo output 9 value"]
13929 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13930 pub servo9_raw: u16,
13931 #[doc = "Servo output 10 value"]
13932 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13933 pub servo10_raw: u16,
13934 #[doc = "Servo output 11 value"]
13935 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13936 pub servo11_raw: u16,
13937 #[doc = "Servo output 12 value"]
13938 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13939 pub servo12_raw: u16,
13940 #[doc = "Servo output 13 value"]
13941 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13942 pub servo13_raw: u16,
13943 #[doc = "Servo output 14 value"]
13944 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13945 pub servo14_raw: u16,
13946 #[doc = "Servo output 15 value"]
13947 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13948 pub servo15_raw: u16,
13949 #[doc = "Servo output 16 value"]
13950 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
13951 pub servo16_raw: u16,
13952}
13953impl SERVO_OUTPUT_RAW_DATA {
13954 pub const ENCODED_LEN: usize = 37usize;
13955 pub const DEFAULT: Self = Self {
13956 time_usec: 0_u32,
13957 servo1_raw: 0_u16,
13958 servo2_raw: 0_u16,
13959 servo3_raw: 0_u16,
13960 servo4_raw: 0_u16,
13961 servo5_raw: 0_u16,
13962 servo6_raw: 0_u16,
13963 servo7_raw: 0_u16,
13964 servo8_raw: 0_u16,
13965 port: 0_u8,
13966 servo9_raw: 0_u16,
13967 servo10_raw: 0_u16,
13968 servo11_raw: 0_u16,
13969 servo12_raw: 0_u16,
13970 servo13_raw: 0_u16,
13971 servo14_raw: 0_u16,
13972 servo15_raw: 0_u16,
13973 servo16_raw: 0_u16,
13974 };
13975 #[cfg(feature = "arbitrary")]
13976 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
13977 use arbitrary::{Arbitrary, Unstructured};
13978 let mut buf = [0u8; 1024];
13979 rng.fill_bytes(&mut buf);
13980 let mut unstructured = Unstructured::new(&buf);
13981 Self::arbitrary(&mut unstructured).unwrap_or_default()
13982 }
13983}
13984impl Default for SERVO_OUTPUT_RAW_DATA {
13985 fn default() -> Self {
13986 Self::DEFAULT.clone()
13987 }
13988}
13989impl MessageData for SERVO_OUTPUT_RAW_DATA {
13990 type Message = MavMessage;
13991 const ID: u32 = 36u32;
13992 const NAME: &'static str = "SERVO_OUTPUT_RAW";
13993 const EXTRA_CRC: u8 = 222u8;
13994 const ENCODED_LEN: usize = 37usize;
13995 fn deser(
13996 _version: MavlinkVersion,
13997 __input: &[u8],
13998 ) -> Result<Self, ::mavlink_core::error::ParserError> {
13999 let avail_len = __input.len();
14000 let mut payload_buf = [0; Self::ENCODED_LEN];
14001 let mut buf = if avail_len < Self::ENCODED_LEN {
14002 payload_buf[0..avail_len].copy_from_slice(__input);
14003 Bytes::new(&payload_buf)
14004 } else {
14005 Bytes::new(__input)
14006 };
14007 let mut __struct = Self::default();
14008 __struct.time_usec = buf.get_u32_le();
14009 __struct.servo1_raw = buf.get_u16_le();
14010 __struct.servo2_raw = buf.get_u16_le();
14011 __struct.servo3_raw = buf.get_u16_le();
14012 __struct.servo4_raw = buf.get_u16_le();
14013 __struct.servo5_raw = buf.get_u16_le();
14014 __struct.servo6_raw = buf.get_u16_le();
14015 __struct.servo7_raw = buf.get_u16_le();
14016 __struct.servo8_raw = buf.get_u16_le();
14017 __struct.port = buf.get_u8();
14018 __struct.servo9_raw = buf.get_u16_le();
14019 __struct.servo10_raw = buf.get_u16_le();
14020 __struct.servo11_raw = buf.get_u16_le();
14021 __struct.servo12_raw = buf.get_u16_le();
14022 __struct.servo13_raw = buf.get_u16_le();
14023 __struct.servo14_raw = buf.get_u16_le();
14024 __struct.servo15_raw = buf.get_u16_le();
14025 __struct.servo16_raw = buf.get_u16_le();
14026 Ok(__struct)
14027 }
14028 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14029 let mut __tmp = BytesMut::new(bytes);
14030 #[allow(clippy::absurd_extreme_comparisons)]
14031 #[allow(unused_comparisons)]
14032 if __tmp.remaining() < Self::ENCODED_LEN {
14033 panic!(
14034 "buffer is too small (need {} bytes, but got {})",
14035 Self::ENCODED_LEN,
14036 __tmp.remaining(),
14037 )
14038 }
14039 __tmp.put_u32_le(self.time_usec);
14040 __tmp.put_u16_le(self.servo1_raw);
14041 __tmp.put_u16_le(self.servo2_raw);
14042 __tmp.put_u16_le(self.servo3_raw);
14043 __tmp.put_u16_le(self.servo4_raw);
14044 __tmp.put_u16_le(self.servo5_raw);
14045 __tmp.put_u16_le(self.servo6_raw);
14046 __tmp.put_u16_le(self.servo7_raw);
14047 __tmp.put_u16_le(self.servo8_raw);
14048 __tmp.put_u8(self.port);
14049 __tmp.put_u16_le(self.servo9_raw);
14050 __tmp.put_u16_le(self.servo10_raw);
14051 __tmp.put_u16_le(self.servo11_raw);
14052 __tmp.put_u16_le(self.servo12_raw);
14053 __tmp.put_u16_le(self.servo13_raw);
14054 __tmp.put_u16_le(self.servo14_raw);
14055 __tmp.put_u16_le(self.servo15_raw);
14056 __tmp.put_u16_le(self.servo16_raw);
14057 if matches!(version, MavlinkVersion::V2) {
14058 let len = __tmp.len();
14059 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14060 } else {
14061 __tmp.len()
14062 }
14063 }
14064}
14065#[doc = "id: 140"]
14066#[doc = "Set the vehicle attitude and body angular rates."]
14067#[derive(Debug, Clone, PartialEq)]
14068#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14069#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14070pub struct ACTUATOR_CONTROL_TARGET_DATA {
14071 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14072 pub time_usec: u64,
14073 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
14074 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14075 pub controls: [f32; 8],
14076 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
14077 pub group_mlx: u8,
14078}
14079impl ACTUATOR_CONTROL_TARGET_DATA {
14080 pub const ENCODED_LEN: usize = 41usize;
14081 pub const DEFAULT: Self = Self {
14082 time_usec: 0_u64,
14083 controls: [0.0_f32; 8usize],
14084 group_mlx: 0_u8,
14085 };
14086 #[cfg(feature = "arbitrary")]
14087 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14088 use arbitrary::{Arbitrary, Unstructured};
14089 let mut buf = [0u8; 1024];
14090 rng.fill_bytes(&mut buf);
14091 let mut unstructured = Unstructured::new(&buf);
14092 Self::arbitrary(&mut unstructured).unwrap_or_default()
14093 }
14094}
14095impl Default for ACTUATOR_CONTROL_TARGET_DATA {
14096 fn default() -> Self {
14097 Self::DEFAULT.clone()
14098 }
14099}
14100impl MessageData for ACTUATOR_CONTROL_TARGET_DATA {
14101 type Message = MavMessage;
14102 const ID: u32 = 140u32;
14103 const NAME: &'static str = "ACTUATOR_CONTROL_TARGET";
14104 const EXTRA_CRC: u8 = 181u8;
14105 const ENCODED_LEN: usize = 41usize;
14106 fn deser(
14107 _version: MavlinkVersion,
14108 __input: &[u8],
14109 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14110 let avail_len = __input.len();
14111 let mut payload_buf = [0; Self::ENCODED_LEN];
14112 let mut buf = if avail_len < Self::ENCODED_LEN {
14113 payload_buf[0..avail_len].copy_from_slice(__input);
14114 Bytes::new(&payload_buf)
14115 } else {
14116 Bytes::new(__input)
14117 };
14118 let mut __struct = Self::default();
14119 __struct.time_usec = buf.get_u64_le();
14120 for v in &mut __struct.controls {
14121 let val = buf.get_f32_le();
14122 *v = val;
14123 }
14124 __struct.group_mlx = buf.get_u8();
14125 Ok(__struct)
14126 }
14127 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14128 let mut __tmp = BytesMut::new(bytes);
14129 #[allow(clippy::absurd_extreme_comparisons)]
14130 #[allow(unused_comparisons)]
14131 if __tmp.remaining() < Self::ENCODED_LEN {
14132 panic!(
14133 "buffer is too small (need {} bytes, but got {})",
14134 Self::ENCODED_LEN,
14135 __tmp.remaining(),
14136 )
14137 }
14138 __tmp.put_u64_le(self.time_usec);
14139 for val in &self.controls {
14140 __tmp.put_f32_le(*val);
14141 }
14142 __tmp.put_u8(self.group_mlx);
14143 if matches!(version, MavlinkVersion::V2) {
14144 let len = __tmp.len();
14145 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14146 } else {
14147 __tmp.len()
14148 }
14149 }
14150}
14151#[doc = "id: 83"]
14152#[doc = "Reports the current commanded attitude of the vehicle as specified by the autopilot. This should match the commands sent in a SET_ATTITUDE_TARGET message if the vehicle is being controlled this way."]
14153#[derive(Debug, Clone, PartialEq)]
14154#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14155#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14156pub struct ATTITUDE_TARGET_DATA {
14157 #[doc = "Timestamp (time since system boot)."]
14158 pub time_boot_ms: u32,
14159 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
14160 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14161 pub q: [f32; 4],
14162 #[doc = "Body roll rate"]
14163 pub body_roll_rate: f32,
14164 #[doc = "Body pitch rate"]
14165 pub body_pitch_rate: f32,
14166 #[doc = "Body yaw rate"]
14167 pub body_yaw_rate: f32,
14168 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
14169 pub thrust: f32,
14170 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
14171 pub type_mask: AttitudeTargetTypemask,
14172}
14173impl ATTITUDE_TARGET_DATA {
14174 pub const ENCODED_LEN: usize = 37usize;
14175 pub const DEFAULT: Self = Self {
14176 time_boot_ms: 0_u32,
14177 q: [0.0_f32; 4usize],
14178 body_roll_rate: 0.0_f32,
14179 body_pitch_rate: 0.0_f32,
14180 body_yaw_rate: 0.0_f32,
14181 thrust: 0.0_f32,
14182 type_mask: AttitudeTargetTypemask::DEFAULT,
14183 };
14184 #[cfg(feature = "arbitrary")]
14185 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14186 use arbitrary::{Arbitrary, Unstructured};
14187 let mut buf = [0u8; 1024];
14188 rng.fill_bytes(&mut buf);
14189 let mut unstructured = Unstructured::new(&buf);
14190 Self::arbitrary(&mut unstructured).unwrap_or_default()
14191 }
14192}
14193impl Default for ATTITUDE_TARGET_DATA {
14194 fn default() -> Self {
14195 Self::DEFAULT.clone()
14196 }
14197}
14198impl MessageData for ATTITUDE_TARGET_DATA {
14199 type Message = MavMessage;
14200 const ID: u32 = 83u32;
14201 const NAME: &'static str = "ATTITUDE_TARGET";
14202 const EXTRA_CRC: u8 = 22u8;
14203 const ENCODED_LEN: usize = 37usize;
14204 fn deser(
14205 _version: MavlinkVersion,
14206 __input: &[u8],
14207 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14208 let avail_len = __input.len();
14209 let mut payload_buf = [0; Self::ENCODED_LEN];
14210 let mut buf = if avail_len < Self::ENCODED_LEN {
14211 payload_buf[0..avail_len].copy_from_slice(__input);
14212 Bytes::new(&payload_buf)
14213 } else {
14214 Bytes::new(__input)
14215 };
14216 let mut __struct = Self::default();
14217 __struct.time_boot_ms = buf.get_u32_le();
14218 for v in &mut __struct.q {
14219 let val = buf.get_f32_le();
14220 *v = val;
14221 }
14222 __struct.body_roll_rate = buf.get_f32_le();
14223 __struct.body_pitch_rate = buf.get_f32_le();
14224 __struct.body_yaw_rate = buf.get_f32_le();
14225 __struct.thrust = buf.get_f32_le();
14226 let tmp = buf.get_u8();
14227 __struct.type_mask = AttitudeTargetTypemask::from_bits(
14228 tmp & AttitudeTargetTypemask::all().bits(),
14229 )
14230 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
14231 flag_type: "AttitudeTargetTypemask",
14232 value: tmp as u32,
14233 })?;
14234 Ok(__struct)
14235 }
14236 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14237 let mut __tmp = BytesMut::new(bytes);
14238 #[allow(clippy::absurd_extreme_comparisons)]
14239 #[allow(unused_comparisons)]
14240 if __tmp.remaining() < Self::ENCODED_LEN {
14241 panic!(
14242 "buffer is too small (need {} bytes, but got {})",
14243 Self::ENCODED_LEN,
14244 __tmp.remaining(),
14245 )
14246 }
14247 __tmp.put_u32_le(self.time_boot_ms);
14248 for val in &self.q {
14249 __tmp.put_f32_le(*val);
14250 }
14251 __tmp.put_f32_le(self.body_roll_rate);
14252 __tmp.put_f32_le(self.body_pitch_rate);
14253 __tmp.put_f32_le(self.body_yaw_rate);
14254 __tmp.put_f32_le(self.thrust);
14255 __tmp.put_u8(self.type_mask.bits());
14256 if matches!(version, MavlinkVersion::V2) {
14257 let len = __tmp.len();
14258 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14259 } else {
14260 __tmp.len()
14261 }
14262 }
14263}
14264#[doc = "id: 26"]
14265#[doc = "The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units."]
14266#[derive(Debug, Clone, PartialEq)]
14267#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14268#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14269pub struct SCALED_IMU_DATA {
14270 #[doc = "Timestamp (time since system boot)."]
14271 pub time_boot_ms: u32,
14272 #[doc = "X acceleration"]
14273 pub xacc: i16,
14274 #[doc = "Y acceleration"]
14275 pub yacc: i16,
14276 #[doc = "Z acceleration"]
14277 pub zacc: i16,
14278 #[doc = "Angular speed around X axis"]
14279 pub xgyro: i16,
14280 #[doc = "Angular speed around Y axis"]
14281 pub ygyro: i16,
14282 #[doc = "Angular speed around Z axis"]
14283 pub zgyro: i16,
14284 #[doc = "X Magnetic field"]
14285 pub xmag: i16,
14286 #[doc = "Y Magnetic field"]
14287 pub ymag: i16,
14288 #[doc = "Z Magnetic field"]
14289 pub zmag: i16,
14290 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
14291 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14292 pub temperature: i16,
14293}
14294impl SCALED_IMU_DATA {
14295 pub const ENCODED_LEN: usize = 24usize;
14296 pub const DEFAULT: Self = Self {
14297 time_boot_ms: 0_u32,
14298 xacc: 0_i16,
14299 yacc: 0_i16,
14300 zacc: 0_i16,
14301 xgyro: 0_i16,
14302 ygyro: 0_i16,
14303 zgyro: 0_i16,
14304 xmag: 0_i16,
14305 ymag: 0_i16,
14306 zmag: 0_i16,
14307 temperature: 0_i16,
14308 };
14309 #[cfg(feature = "arbitrary")]
14310 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14311 use arbitrary::{Arbitrary, Unstructured};
14312 let mut buf = [0u8; 1024];
14313 rng.fill_bytes(&mut buf);
14314 let mut unstructured = Unstructured::new(&buf);
14315 Self::arbitrary(&mut unstructured).unwrap_or_default()
14316 }
14317}
14318impl Default for SCALED_IMU_DATA {
14319 fn default() -> Self {
14320 Self::DEFAULT.clone()
14321 }
14322}
14323impl MessageData for SCALED_IMU_DATA {
14324 type Message = MavMessage;
14325 const ID: u32 = 26u32;
14326 const NAME: &'static str = "SCALED_IMU";
14327 const EXTRA_CRC: u8 = 170u8;
14328 const ENCODED_LEN: usize = 24usize;
14329 fn deser(
14330 _version: MavlinkVersion,
14331 __input: &[u8],
14332 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14333 let avail_len = __input.len();
14334 let mut payload_buf = [0; Self::ENCODED_LEN];
14335 let mut buf = if avail_len < Self::ENCODED_LEN {
14336 payload_buf[0..avail_len].copy_from_slice(__input);
14337 Bytes::new(&payload_buf)
14338 } else {
14339 Bytes::new(__input)
14340 };
14341 let mut __struct = Self::default();
14342 __struct.time_boot_ms = buf.get_u32_le();
14343 __struct.xacc = buf.get_i16_le();
14344 __struct.yacc = buf.get_i16_le();
14345 __struct.zacc = buf.get_i16_le();
14346 __struct.xgyro = buf.get_i16_le();
14347 __struct.ygyro = buf.get_i16_le();
14348 __struct.zgyro = buf.get_i16_le();
14349 __struct.xmag = buf.get_i16_le();
14350 __struct.ymag = buf.get_i16_le();
14351 __struct.zmag = buf.get_i16_le();
14352 __struct.temperature = buf.get_i16_le();
14353 Ok(__struct)
14354 }
14355 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14356 let mut __tmp = BytesMut::new(bytes);
14357 #[allow(clippy::absurd_extreme_comparisons)]
14358 #[allow(unused_comparisons)]
14359 if __tmp.remaining() < Self::ENCODED_LEN {
14360 panic!(
14361 "buffer is too small (need {} bytes, but got {})",
14362 Self::ENCODED_LEN,
14363 __tmp.remaining(),
14364 )
14365 }
14366 __tmp.put_u32_le(self.time_boot_ms);
14367 __tmp.put_i16_le(self.xacc);
14368 __tmp.put_i16_le(self.yacc);
14369 __tmp.put_i16_le(self.zacc);
14370 __tmp.put_i16_le(self.xgyro);
14371 __tmp.put_i16_le(self.ygyro);
14372 __tmp.put_i16_le(self.zgyro);
14373 __tmp.put_i16_le(self.xmag);
14374 __tmp.put_i16_le(self.ymag);
14375 __tmp.put_i16_le(self.zmag);
14376 __tmp.put_i16_le(self.temperature);
14377 if matches!(version, MavlinkVersion::V2) {
14378 let len = __tmp.len();
14379 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14380 } else {
14381 __tmp.len()
14382 }
14383 }
14384}
14385#[doc = "id: 253"]
14386#[doc = "Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz)."]
14387#[derive(Debug, Clone, PartialEq)]
14388#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14389#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14390pub struct STATUSTEXT_DATA {
14391 #[doc = "Severity of status. Relies on the definitions within RFC-5424."]
14392 pub severity: MavSeverity,
14393 #[doc = "Status text message, without null termination character"]
14394 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14395 pub text: [u8; 50],
14396 #[doc = "Unique (opaque) identifier for this statustext message. May be used to reassemble a logical long-statustext message from a sequence of chunks. A value of zero indicates this is the only chunk in the sequence and the message can be emitted immediately."]
14397 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14398 pub id: u16,
14399 #[doc = "This chunk's sequence number; indexing is from zero. Any null character in the text field is taken to mean this was the last chunk."]
14400 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14401 pub chunk_seq: u8,
14402}
14403impl STATUSTEXT_DATA {
14404 pub const ENCODED_LEN: usize = 54usize;
14405 pub const DEFAULT: Self = Self {
14406 severity: MavSeverity::DEFAULT,
14407 text: [0_u8; 50usize],
14408 id: 0_u16,
14409 chunk_seq: 0_u8,
14410 };
14411 #[cfg(feature = "arbitrary")]
14412 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14413 use arbitrary::{Arbitrary, Unstructured};
14414 let mut buf = [0u8; 1024];
14415 rng.fill_bytes(&mut buf);
14416 let mut unstructured = Unstructured::new(&buf);
14417 Self::arbitrary(&mut unstructured).unwrap_or_default()
14418 }
14419}
14420impl Default for STATUSTEXT_DATA {
14421 fn default() -> Self {
14422 Self::DEFAULT.clone()
14423 }
14424}
14425impl MessageData for STATUSTEXT_DATA {
14426 type Message = MavMessage;
14427 const ID: u32 = 253u32;
14428 const NAME: &'static str = "STATUSTEXT";
14429 const EXTRA_CRC: u8 = 83u8;
14430 const ENCODED_LEN: usize = 54usize;
14431 fn deser(
14432 _version: MavlinkVersion,
14433 __input: &[u8],
14434 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14435 let avail_len = __input.len();
14436 let mut payload_buf = [0; Self::ENCODED_LEN];
14437 let mut buf = if avail_len < Self::ENCODED_LEN {
14438 payload_buf[0..avail_len].copy_from_slice(__input);
14439 Bytes::new(&payload_buf)
14440 } else {
14441 Bytes::new(__input)
14442 };
14443 let mut __struct = Self::default();
14444 let tmp = buf.get_u8();
14445 __struct.severity =
14446 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14447 enum_type: "MavSeverity",
14448 value: tmp as u32,
14449 })?;
14450 for v in &mut __struct.text {
14451 let val = buf.get_u8();
14452 *v = val;
14453 }
14454 __struct.id = buf.get_u16_le();
14455 __struct.chunk_seq = buf.get_u8();
14456 Ok(__struct)
14457 }
14458 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14459 let mut __tmp = BytesMut::new(bytes);
14460 #[allow(clippy::absurd_extreme_comparisons)]
14461 #[allow(unused_comparisons)]
14462 if __tmp.remaining() < Self::ENCODED_LEN {
14463 panic!(
14464 "buffer is too small (need {} bytes, but got {})",
14465 Self::ENCODED_LEN,
14466 __tmp.remaining(),
14467 )
14468 }
14469 __tmp.put_u8(self.severity as u8);
14470 for val in &self.text {
14471 __tmp.put_u8(*val);
14472 }
14473 __tmp.put_u16_le(self.id);
14474 __tmp.put_u8(self.chunk_seq);
14475 if matches!(version, MavlinkVersion::V2) {
14476 let len = __tmp.len();
14477 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14478 } else {
14479 __tmp.len()
14480 }
14481 }
14482}
14483#[doc = "id: 141"]
14484#[doc = "The current system altitude."]
14485#[derive(Debug, Clone, PartialEq)]
14486#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14487#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14488pub struct ALTITUDE_DATA {
14489 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14490 pub time_usec: u64,
14491 #[doc = "This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights."]
14492 pub altitude_monotonic: f32,
14493 #[doc = "This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude."]
14494 pub altitude_amsl: f32,
14495 #[doc = "This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive."]
14496 pub altitude_local: f32,
14497 #[doc = "This is the altitude above the home position. It resets on each change of the current home position."]
14498 pub altitude_relative: f32,
14499 #[doc = "This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown."]
14500 pub altitude_terrain: f32,
14501 #[doc = "This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available."]
14502 pub bottom_clearance: f32,
14503}
14504impl ALTITUDE_DATA {
14505 pub const ENCODED_LEN: usize = 32usize;
14506 pub const DEFAULT: Self = Self {
14507 time_usec: 0_u64,
14508 altitude_monotonic: 0.0_f32,
14509 altitude_amsl: 0.0_f32,
14510 altitude_local: 0.0_f32,
14511 altitude_relative: 0.0_f32,
14512 altitude_terrain: 0.0_f32,
14513 bottom_clearance: 0.0_f32,
14514 };
14515 #[cfg(feature = "arbitrary")]
14516 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14517 use arbitrary::{Arbitrary, Unstructured};
14518 let mut buf = [0u8; 1024];
14519 rng.fill_bytes(&mut buf);
14520 let mut unstructured = Unstructured::new(&buf);
14521 Self::arbitrary(&mut unstructured).unwrap_or_default()
14522 }
14523}
14524impl Default for ALTITUDE_DATA {
14525 fn default() -> Self {
14526 Self::DEFAULT.clone()
14527 }
14528}
14529impl MessageData for ALTITUDE_DATA {
14530 type Message = MavMessage;
14531 const ID: u32 = 141u32;
14532 const NAME: &'static str = "ALTITUDE";
14533 const EXTRA_CRC: u8 = 47u8;
14534 const ENCODED_LEN: usize = 32usize;
14535 fn deser(
14536 _version: MavlinkVersion,
14537 __input: &[u8],
14538 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14539 let avail_len = __input.len();
14540 let mut payload_buf = [0; Self::ENCODED_LEN];
14541 let mut buf = if avail_len < Self::ENCODED_LEN {
14542 payload_buf[0..avail_len].copy_from_slice(__input);
14543 Bytes::new(&payload_buf)
14544 } else {
14545 Bytes::new(__input)
14546 };
14547 let mut __struct = Self::default();
14548 __struct.time_usec = buf.get_u64_le();
14549 __struct.altitude_monotonic = buf.get_f32_le();
14550 __struct.altitude_amsl = buf.get_f32_le();
14551 __struct.altitude_local = buf.get_f32_le();
14552 __struct.altitude_relative = buf.get_f32_le();
14553 __struct.altitude_terrain = buf.get_f32_le();
14554 __struct.bottom_clearance = buf.get_f32_le();
14555 Ok(__struct)
14556 }
14557 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14558 let mut __tmp = BytesMut::new(bytes);
14559 #[allow(clippy::absurd_extreme_comparisons)]
14560 #[allow(unused_comparisons)]
14561 if __tmp.remaining() < Self::ENCODED_LEN {
14562 panic!(
14563 "buffer is too small (need {} bytes, but got {})",
14564 Self::ENCODED_LEN,
14565 __tmp.remaining(),
14566 )
14567 }
14568 __tmp.put_u64_le(self.time_usec);
14569 __tmp.put_f32_le(self.altitude_monotonic);
14570 __tmp.put_f32_le(self.altitude_amsl);
14571 __tmp.put_f32_le(self.altitude_local);
14572 __tmp.put_f32_le(self.altitude_relative);
14573 __tmp.put_f32_le(self.altitude_terrain);
14574 __tmp.put_f32_le(self.bottom_clearance);
14575 if matches!(version, MavlinkVersion::V2) {
14576 let len = __tmp.len();
14577 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14578 } else {
14579 __tmp.len()
14580 }
14581 }
14582}
14583#[doc = "id: 5"]
14584#[doc = "Request to control this MAV."]
14585#[derive(Debug, Clone, PartialEq)]
14586#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14587#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14588pub struct CHANGE_OPERATOR_CONTROL_DATA {
14589 #[doc = "System the GCS requests control for"]
14590 pub target_system: u8,
14591 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
14592 pub control_request: u8,
14593 #[doc = "0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch."]
14594 pub version: u8,
14595 #[doc = "Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and \"!?,.-\""]
14596 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
14597 pub passkey: [u8; 25],
14598}
14599impl CHANGE_OPERATOR_CONTROL_DATA {
14600 pub const ENCODED_LEN: usize = 28usize;
14601 pub const DEFAULT: Self = Self {
14602 target_system: 0_u8,
14603 control_request: 0_u8,
14604 version: 0_u8,
14605 passkey: [0_u8; 25usize],
14606 };
14607 #[cfg(feature = "arbitrary")]
14608 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14609 use arbitrary::{Arbitrary, Unstructured};
14610 let mut buf = [0u8; 1024];
14611 rng.fill_bytes(&mut buf);
14612 let mut unstructured = Unstructured::new(&buf);
14613 Self::arbitrary(&mut unstructured).unwrap_or_default()
14614 }
14615}
14616impl Default for CHANGE_OPERATOR_CONTROL_DATA {
14617 fn default() -> Self {
14618 Self::DEFAULT.clone()
14619 }
14620}
14621impl MessageData for CHANGE_OPERATOR_CONTROL_DATA {
14622 type Message = MavMessage;
14623 const ID: u32 = 5u32;
14624 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL";
14625 const EXTRA_CRC: u8 = 217u8;
14626 const ENCODED_LEN: usize = 28usize;
14627 fn deser(
14628 _version: MavlinkVersion,
14629 __input: &[u8],
14630 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14631 let avail_len = __input.len();
14632 let mut payload_buf = [0; Self::ENCODED_LEN];
14633 let mut buf = if avail_len < Self::ENCODED_LEN {
14634 payload_buf[0..avail_len].copy_from_slice(__input);
14635 Bytes::new(&payload_buf)
14636 } else {
14637 Bytes::new(__input)
14638 };
14639 let mut __struct = Self::default();
14640 __struct.target_system = buf.get_u8();
14641 __struct.control_request = buf.get_u8();
14642 __struct.version = buf.get_u8();
14643 for v in &mut __struct.passkey {
14644 let val = buf.get_u8();
14645 *v = val;
14646 }
14647 Ok(__struct)
14648 }
14649 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14650 let mut __tmp = BytesMut::new(bytes);
14651 #[allow(clippy::absurd_extreme_comparisons)]
14652 #[allow(unused_comparisons)]
14653 if __tmp.remaining() < Self::ENCODED_LEN {
14654 panic!(
14655 "buffer is too small (need {} bytes, but got {})",
14656 Self::ENCODED_LEN,
14657 __tmp.remaining(),
14658 )
14659 }
14660 __tmp.put_u8(self.target_system);
14661 __tmp.put_u8(self.control_request);
14662 __tmp.put_u8(self.version);
14663 for val in &self.passkey {
14664 __tmp.put_u8(*val);
14665 }
14666 if matches!(version, MavlinkVersion::V2) {
14667 let len = __tmp.len();
14668 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14669 } else {
14670 __tmp.len()
14671 }
14672 }
14673}
14674#[doc = "id: 339"]
14675#[doc = "RPM sensor data message."]
14676#[derive(Debug, Clone, PartialEq)]
14677#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14678#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14679pub struct RAW_RPM_DATA {
14680 #[doc = "Indicated rate"]
14681 pub frequency: f32,
14682 #[doc = "Index of this RPM sensor (0-indexed)"]
14683 pub index: u8,
14684}
14685impl RAW_RPM_DATA {
14686 pub const ENCODED_LEN: usize = 5usize;
14687 pub const DEFAULT: Self = Self {
14688 frequency: 0.0_f32,
14689 index: 0_u8,
14690 };
14691 #[cfg(feature = "arbitrary")]
14692 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14693 use arbitrary::{Arbitrary, Unstructured};
14694 let mut buf = [0u8; 1024];
14695 rng.fill_bytes(&mut buf);
14696 let mut unstructured = Unstructured::new(&buf);
14697 Self::arbitrary(&mut unstructured).unwrap_or_default()
14698 }
14699}
14700impl Default for RAW_RPM_DATA {
14701 fn default() -> Self {
14702 Self::DEFAULT.clone()
14703 }
14704}
14705impl MessageData for RAW_RPM_DATA {
14706 type Message = MavMessage;
14707 const ID: u32 = 339u32;
14708 const NAME: &'static str = "RAW_RPM";
14709 const EXTRA_CRC: u8 = 199u8;
14710 const ENCODED_LEN: usize = 5usize;
14711 fn deser(
14712 _version: MavlinkVersion,
14713 __input: &[u8],
14714 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14715 let avail_len = __input.len();
14716 let mut payload_buf = [0; Self::ENCODED_LEN];
14717 let mut buf = if avail_len < Self::ENCODED_LEN {
14718 payload_buf[0..avail_len].copy_from_slice(__input);
14719 Bytes::new(&payload_buf)
14720 } else {
14721 Bytes::new(__input)
14722 };
14723 let mut __struct = Self::default();
14724 __struct.frequency = buf.get_f32_le();
14725 __struct.index = buf.get_u8();
14726 Ok(__struct)
14727 }
14728 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14729 let mut __tmp = BytesMut::new(bytes);
14730 #[allow(clippy::absurd_extreme_comparisons)]
14731 #[allow(unused_comparisons)]
14732 if __tmp.remaining() < Self::ENCODED_LEN {
14733 panic!(
14734 "buffer is too small (need {} bytes, but got {})",
14735 Self::ENCODED_LEN,
14736 __tmp.remaining(),
14737 )
14738 }
14739 __tmp.put_f32_le(self.frequency);
14740 __tmp.put_u8(self.index);
14741 if matches!(version, MavlinkVersion::V2) {
14742 let len = __tmp.len();
14743 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14744 } else {
14745 __tmp.len()
14746 }
14747 }
14748}
14749#[doc = "id: 128"]
14750#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
14751#[derive(Debug, Clone, PartialEq)]
14752#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14753#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14754pub struct GPS2_RTK_DATA {
14755 #[doc = "Time since boot of last baseline message received."]
14756 pub time_last_baseline_ms: u32,
14757 #[doc = "GPS Time of Week of last baseline"]
14758 pub tow: u32,
14759 #[doc = "Current baseline in ECEF x or NED north component."]
14760 pub baseline_a_mm: i32,
14761 #[doc = "Current baseline in ECEF y or NED east component."]
14762 pub baseline_b_mm: i32,
14763 #[doc = "Current baseline in ECEF z or NED down component."]
14764 pub baseline_c_mm: i32,
14765 #[doc = "Current estimate of baseline accuracy."]
14766 pub accuracy: u32,
14767 #[doc = "Current number of integer ambiguity hypotheses."]
14768 pub iar_num_hypotheses: i32,
14769 #[doc = "GPS Week Number of last baseline"]
14770 pub wn: u16,
14771 #[doc = "Identification of connected RTK receiver."]
14772 pub rtk_receiver_id: u8,
14773 #[doc = "GPS-specific health report for RTK data."]
14774 pub rtk_health: u8,
14775 #[doc = "Rate of baseline messages being received by GPS"]
14776 pub rtk_rate: u8,
14777 #[doc = "Current number of sats used for RTK calculation."]
14778 pub nsats: u8,
14779 #[doc = "Coordinate system of baseline"]
14780 pub baseline_coords_type: RtkBaselineCoordinateSystem,
14781}
14782impl GPS2_RTK_DATA {
14783 pub const ENCODED_LEN: usize = 35usize;
14784 pub const DEFAULT: Self = Self {
14785 time_last_baseline_ms: 0_u32,
14786 tow: 0_u32,
14787 baseline_a_mm: 0_i32,
14788 baseline_b_mm: 0_i32,
14789 baseline_c_mm: 0_i32,
14790 accuracy: 0_u32,
14791 iar_num_hypotheses: 0_i32,
14792 wn: 0_u16,
14793 rtk_receiver_id: 0_u8,
14794 rtk_health: 0_u8,
14795 rtk_rate: 0_u8,
14796 nsats: 0_u8,
14797 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
14798 };
14799 #[cfg(feature = "arbitrary")]
14800 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14801 use arbitrary::{Arbitrary, Unstructured};
14802 let mut buf = [0u8; 1024];
14803 rng.fill_bytes(&mut buf);
14804 let mut unstructured = Unstructured::new(&buf);
14805 Self::arbitrary(&mut unstructured).unwrap_or_default()
14806 }
14807}
14808impl Default for GPS2_RTK_DATA {
14809 fn default() -> Self {
14810 Self::DEFAULT.clone()
14811 }
14812}
14813impl MessageData for GPS2_RTK_DATA {
14814 type Message = MavMessage;
14815 const ID: u32 = 128u32;
14816 const NAME: &'static str = "GPS2_RTK";
14817 const EXTRA_CRC: u8 = 226u8;
14818 const ENCODED_LEN: usize = 35usize;
14819 fn deser(
14820 _version: MavlinkVersion,
14821 __input: &[u8],
14822 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14823 let avail_len = __input.len();
14824 let mut payload_buf = [0; Self::ENCODED_LEN];
14825 let mut buf = if avail_len < Self::ENCODED_LEN {
14826 payload_buf[0..avail_len].copy_from_slice(__input);
14827 Bytes::new(&payload_buf)
14828 } else {
14829 Bytes::new(__input)
14830 };
14831 let mut __struct = Self::default();
14832 __struct.time_last_baseline_ms = buf.get_u32_le();
14833 __struct.tow = buf.get_u32_le();
14834 __struct.baseline_a_mm = buf.get_i32_le();
14835 __struct.baseline_b_mm = buf.get_i32_le();
14836 __struct.baseline_c_mm = buf.get_i32_le();
14837 __struct.accuracy = buf.get_u32_le();
14838 __struct.iar_num_hypotheses = buf.get_i32_le();
14839 __struct.wn = buf.get_u16_le();
14840 __struct.rtk_receiver_id = buf.get_u8();
14841 __struct.rtk_health = buf.get_u8();
14842 __struct.rtk_rate = buf.get_u8();
14843 __struct.nsats = buf.get_u8();
14844 let tmp = buf.get_u8();
14845 __struct.baseline_coords_type =
14846 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
14847 enum_type: "RtkBaselineCoordinateSystem",
14848 value: tmp as u32,
14849 })?;
14850 Ok(__struct)
14851 }
14852 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14853 let mut __tmp = BytesMut::new(bytes);
14854 #[allow(clippy::absurd_extreme_comparisons)]
14855 #[allow(unused_comparisons)]
14856 if __tmp.remaining() < Self::ENCODED_LEN {
14857 panic!(
14858 "buffer is too small (need {} bytes, but got {})",
14859 Self::ENCODED_LEN,
14860 __tmp.remaining(),
14861 )
14862 }
14863 __tmp.put_u32_le(self.time_last_baseline_ms);
14864 __tmp.put_u32_le(self.tow);
14865 __tmp.put_i32_le(self.baseline_a_mm);
14866 __tmp.put_i32_le(self.baseline_b_mm);
14867 __tmp.put_i32_le(self.baseline_c_mm);
14868 __tmp.put_u32_le(self.accuracy);
14869 __tmp.put_i32_le(self.iar_num_hypotheses);
14870 __tmp.put_u16_le(self.wn);
14871 __tmp.put_u8(self.rtk_receiver_id);
14872 __tmp.put_u8(self.rtk_health);
14873 __tmp.put_u8(self.rtk_rate);
14874 __tmp.put_u8(self.nsats);
14875 __tmp.put_u8(self.baseline_coords_type as u8);
14876 if matches!(version, MavlinkVersion::V2) {
14877 let len = __tmp.len();
14878 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14879 } else {
14880 __tmp.len()
14881 }
14882 }
14883}
14884#[doc = "id: 100"]
14885#[doc = "Optical flow from a flow sensor (e.g. optical mouse sensor)."]
14886#[derive(Debug, Clone, PartialEq)]
14887#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
14888#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
14889pub struct OPTICAL_FLOW_DATA {
14890 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
14891 pub time_usec: u64,
14892 #[doc = "Flow in x-sensor direction, angular-speed compensated"]
14893 pub flow_comp_m_x: f32,
14894 #[doc = "Flow in y-sensor direction, angular-speed compensated"]
14895 pub flow_comp_m_y: f32,
14896 #[doc = "Ground distance. Positive value: distance known. Negative value: Unknown distance"]
14897 pub ground_distance: f32,
14898 #[doc = "Flow in x-sensor direction"]
14899 pub flow_x: i16,
14900 #[doc = "Flow in y-sensor direction"]
14901 pub flow_y: i16,
14902 #[doc = "Sensor ID"]
14903 pub sensor_id: u8,
14904 #[doc = "Optical flow quality / confidence. 0: bad, 255: maximum quality"]
14905 pub quality: u8,
14906 #[doc = "Flow rate about X axis"]
14907 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14908 pub flow_rate_x: f32,
14909 #[doc = "Flow rate about Y axis"]
14910 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
14911 pub flow_rate_y: f32,
14912}
14913impl OPTICAL_FLOW_DATA {
14914 pub const ENCODED_LEN: usize = 34usize;
14915 pub const DEFAULT: Self = Self {
14916 time_usec: 0_u64,
14917 flow_comp_m_x: 0.0_f32,
14918 flow_comp_m_y: 0.0_f32,
14919 ground_distance: 0.0_f32,
14920 flow_x: 0_i16,
14921 flow_y: 0_i16,
14922 sensor_id: 0_u8,
14923 quality: 0_u8,
14924 flow_rate_x: 0.0_f32,
14925 flow_rate_y: 0.0_f32,
14926 };
14927 #[cfg(feature = "arbitrary")]
14928 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
14929 use arbitrary::{Arbitrary, Unstructured};
14930 let mut buf = [0u8; 1024];
14931 rng.fill_bytes(&mut buf);
14932 let mut unstructured = Unstructured::new(&buf);
14933 Self::arbitrary(&mut unstructured).unwrap_or_default()
14934 }
14935}
14936impl Default for OPTICAL_FLOW_DATA {
14937 fn default() -> Self {
14938 Self::DEFAULT.clone()
14939 }
14940}
14941impl MessageData for OPTICAL_FLOW_DATA {
14942 type Message = MavMessage;
14943 const ID: u32 = 100u32;
14944 const NAME: &'static str = "OPTICAL_FLOW";
14945 const EXTRA_CRC: u8 = 175u8;
14946 const ENCODED_LEN: usize = 34usize;
14947 fn deser(
14948 _version: MavlinkVersion,
14949 __input: &[u8],
14950 ) -> Result<Self, ::mavlink_core::error::ParserError> {
14951 let avail_len = __input.len();
14952 let mut payload_buf = [0; Self::ENCODED_LEN];
14953 let mut buf = if avail_len < Self::ENCODED_LEN {
14954 payload_buf[0..avail_len].copy_from_slice(__input);
14955 Bytes::new(&payload_buf)
14956 } else {
14957 Bytes::new(__input)
14958 };
14959 let mut __struct = Self::default();
14960 __struct.time_usec = buf.get_u64_le();
14961 __struct.flow_comp_m_x = buf.get_f32_le();
14962 __struct.flow_comp_m_y = buf.get_f32_le();
14963 __struct.ground_distance = buf.get_f32_le();
14964 __struct.flow_x = buf.get_i16_le();
14965 __struct.flow_y = buf.get_i16_le();
14966 __struct.sensor_id = buf.get_u8();
14967 __struct.quality = buf.get_u8();
14968 __struct.flow_rate_x = buf.get_f32_le();
14969 __struct.flow_rate_y = buf.get_f32_le();
14970 Ok(__struct)
14971 }
14972 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
14973 let mut __tmp = BytesMut::new(bytes);
14974 #[allow(clippy::absurd_extreme_comparisons)]
14975 #[allow(unused_comparisons)]
14976 if __tmp.remaining() < Self::ENCODED_LEN {
14977 panic!(
14978 "buffer is too small (need {} bytes, but got {})",
14979 Self::ENCODED_LEN,
14980 __tmp.remaining(),
14981 )
14982 }
14983 __tmp.put_u64_le(self.time_usec);
14984 __tmp.put_f32_le(self.flow_comp_m_x);
14985 __tmp.put_f32_le(self.flow_comp_m_y);
14986 __tmp.put_f32_le(self.ground_distance);
14987 __tmp.put_i16_le(self.flow_x);
14988 __tmp.put_i16_le(self.flow_y);
14989 __tmp.put_u8(self.sensor_id);
14990 __tmp.put_u8(self.quality);
14991 __tmp.put_f32_le(self.flow_rate_x);
14992 __tmp.put_f32_le(self.flow_rate_y);
14993 if matches!(version, MavlinkVersion::V2) {
14994 let len = __tmp.len();
14995 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
14996 } else {
14997 __tmp.len()
14998 }
14999 }
15000}
15001#[doc = "id: 134"]
15002#[doc = "Terrain data sent from GCS. The lat/lon and grid_spacing must be the same as a lat/lon from a TERRAIN_REQUEST. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
15003#[derive(Debug, Clone, PartialEq)]
15004#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15005#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15006pub struct TERRAIN_DATA_DATA {
15007 #[doc = "Latitude of SW corner of first grid"]
15008 pub lat: i32,
15009 #[doc = "Longitude of SW corner of first grid"]
15010 pub lon: i32,
15011 #[doc = "Grid spacing"]
15012 pub grid_spacing: u16,
15013 #[doc = "Terrain data MSL"]
15014 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15015 pub data: [i16; 16],
15016 #[doc = "bit within the terrain request mask"]
15017 pub gridbit: u8,
15018}
15019impl TERRAIN_DATA_DATA {
15020 pub const ENCODED_LEN: usize = 43usize;
15021 pub const DEFAULT: Self = Self {
15022 lat: 0_i32,
15023 lon: 0_i32,
15024 grid_spacing: 0_u16,
15025 data: [0_i16; 16usize],
15026 gridbit: 0_u8,
15027 };
15028 #[cfg(feature = "arbitrary")]
15029 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15030 use arbitrary::{Arbitrary, Unstructured};
15031 let mut buf = [0u8; 1024];
15032 rng.fill_bytes(&mut buf);
15033 let mut unstructured = Unstructured::new(&buf);
15034 Self::arbitrary(&mut unstructured).unwrap_or_default()
15035 }
15036}
15037impl Default for TERRAIN_DATA_DATA {
15038 fn default() -> Self {
15039 Self::DEFAULT.clone()
15040 }
15041}
15042impl MessageData for TERRAIN_DATA_DATA {
15043 type Message = MavMessage;
15044 const ID: u32 = 134u32;
15045 const NAME: &'static str = "TERRAIN_DATA";
15046 const EXTRA_CRC: u8 = 229u8;
15047 const ENCODED_LEN: usize = 43usize;
15048 fn deser(
15049 _version: MavlinkVersion,
15050 __input: &[u8],
15051 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15052 let avail_len = __input.len();
15053 let mut payload_buf = [0; Self::ENCODED_LEN];
15054 let mut buf = if avail_len < Self::ENCODED_LEN {
15055 payload_buf[0..avail_len].copy_from_slice(__input);
15056 Bytes::new(&payload_buf)
15057 } else {
15058 Bytes::new(__input)
15059 };
15060 let mut __struct = Self::default();
15061 __struct.lat = buf.get_i32_le();
15062 __struct.lon = buf.get_i32_le();
15063 __struct.grid_spacing = buf.get_u16_le();
15064 for v in &mut __struct.data {
15065 let val = buf.get_i16_le();
15066 *v = val;
15067 }
15068 __struct.gridbit = buf.get_u8();
15069 Ok(__struct)
15070 }
15071 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15072 let mut __tmp = BytesMut::new(bytes);
15073 #[allow(clippy::absurd_extreme_comparisons)]
15074 #[allow(unused_comparisons)]
15075 if __tmp.remaining() < Self::ENCODED_LEN {
15076 panic!(
15077 "buffer is too small (need {} bytes, but got {})",
15078 Self::ENCODED_LEN,
15079 __tmp.remaining(),
15080 )
15081 }
15082 __tmp.put_i32_le(self.lat);
15083 __tmp.put_i32_le(self.lon);
15084 __tmp.put_u16_le(self.grid_spacing);
15085 for val in &self.data {
15086 __tmp.put_i16_le(*val);
15087 }
15088 __tmp.put_u8(self.gridbit);
15089 if matches!(version, MavlinkVersion::V2) {
15090 let len = __tmp.len();
15091 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15092 } else {
15093 __tmp.len()
15094 }
15095 }
15096}
15097#[doc = "id: 360"]
15098#[doc = "Vehicle status report that is sent out while orbit execution is in progress (see MAV_CMD_DO_ORBIT)."]
15099#[derive(Debug, Clone, PartialEq)]
15100#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15101#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15102pub struct ORBIT_EXECUTION_STATUS_DATA {
15103 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15104 pub time_usec: u64,
15105 #[doc = "Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise."]
15106 pub radius: f32,
15107 #[doc = "X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
15108 pub x: i32,
15109 #[doc = "Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7."]
15110 pub y: i32,
15111 #[doc = "Altitude of center point. Coordinate system depends on frame field."]
15112 pub z: f32,
15113 #[doc = "The coordinate system of the fields: x, y, z."]
15114 pub frame: MavFrame,
15115}
15116impl ORBIT_EXECUTION_STATUS_DATA {
15117 pub const ENCODED_LEN: usize = 25usize;
15118 pub const DEFAULT: Self = Self {
15119 time_usec: 0_u64,
15120 radius: 0.0_f32,
15121 x: 0_i32,
15122 y: 0_i32,
15123 z: 0.0_f32,
15124 frame: MavFrame::DEFAULT,
15125 };
15126 #[cfg(feature = "arbitrary")]
15127 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15128 use arbitrary::{Arbitrary, Unstructured};
15129 let mut buf = [0u8; 1024];
15130 rng.fill_bytes(&mut buf);
15131 let mut unstructured = Unstructured::new(&buf);
15132 Self::arbitrary(&mut unstructured).unwrap_or_default()
15133 }
15134}
15135impl Default for ORBIT_EXECUTION_STATUS_DATA {
15136 fn default() -> Self {
15137 Self::DEFAULT.clone()
15138 }
15139}
15140impl MessageData for ORBIT_EXECUTION_STATUS_DATA {
15141 type Message = MavMessage;
15142 const ID: u32 = 360u32;
15143 const NAME: &'static str = "ORBIT_EXECUTION_STATUS";
15144 const EXTRA_CRC: u8 = 11u8;
15145 const ENCODED_LEN: usize = 25usize;
15146 fn deser(
15147 _version: MavlinkVersion,
15148 __input: &[u8],
15149 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15150 let avail_len = __input.len();
15151 let mut payload_buf = [0; Self::ENCODED_LEN];
15152 let mut buf = if avail_len < Self::ENCODED_LEN {
15153 payload_buf[0..avail_len].copy_from_slice(__input);
15154 Bytes::new(&payload_buf)
15155 } else {
15156 Bytes::new(__input)
15157 };
15158 let mut __struct = Self::default();
15159 __struct.time_usec = buf.get_u64_le();
15160 __struct.radius = buf.get_f32_le();
15161 __struct.x = buf.get_i32_le();
15162 __struct.y = buf.get_i32_le();
15163 __struct.z = buf.get_f32_le();
15164 let tmp = buf.get_u8();
15165 __struct.frame =
15166 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15167 enum_type: "MavFrame",
15168 value: tmp as u32,
15169 })?;
15170 Ok(__struct)
15171 }
15172 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15173 let mut __tmp = BytesMut::new(bytes);
15174 #[allow(clippy::absurd_extreme_comparisons)]
15175 #[allow(unused_comparisons)]
15176 if __tmp.remaining() < Self::ENCODED_LEN {
15177 panic!(
15178 "buffer is too small (need {} bytes, but got {})",
15179 Self::ENCODED_LEN,
15180 __tmp.remaining(),
15181 )
15182 }
15183 __tmp.put_u64_le(self.time_usec);
15184 __tmp.put_f32_le(self.radius);
15185 __tmp.put_i32_le(self.x);
15186 __tmp.put_i32_le(self.y);
15187 __tmp.put_f32_le(self.z);
15188 __tmp.put_u8(self.frame as u8);
15189 if matches!(version, MavlinkVersion::V2) {
15190 let len = __tmp.len();
15191 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15192 } else {
15193 __tmp.len()
15194 }
15195 }
15196}
15197#[doc = "id: 33"]
15198#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient."]
15199#[derive(Debug, Clone, PartialEq)]
15200#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15201#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15202pub struct GLOBAL_POSITION_INT_DATA {
15203 #[doc = "Timestamp (time since system boot)."]
15204 pub time_boot_ms: u32,
15205 #[doc = "Latitude, expressed"]
15206 pub lat: i32,
15207 #[doc = "Longitude, expressed"]
15208 pub lon: i32,
15209 #[doc = "Altitude (MSL). Note that virtually all GPS modules provide both WGS84 and MSL."]
15210 pub alt: i32,
15211 #[doc = "Altitude above home"]
15212 pub relative_alt: i32,
15213 #[doc = "Ground X Speed (Latitude, positive north)"]
15214 pub vx: i16,
15215 #[doc = "Ground Y Speed (Longitude, positive east)"]
15216 pub vy: i16,
15217 #[doc = "Ground Z Speed (Altitude, positive down)"]
15218 pub vz: i16,
15219 #[doc = "Vehicle heading (yaw angle), 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
15220 pub hdg: u16,
15221}
15222impl GLOBAL_POSITION_INT_DATA {
15223 pub const ENCODED_LEN: usize = 28usize;
15224 pub const DEFAULT: Self = Self {
15225 time_boot_ms: 0_u32,
15226 lat: 0_i32,
15227 lon: 0_i32,
15228 alt: 0_i32,
15229 relative_alt: 0_i32,
15230 vx: 0_i16,
15231 vy: 0_i16,
15232 vz: 0_i16,
15233 hdg: 0_u16,
15234 };
15235 #[cfg(feature = "arbitrary")]
15236 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15237 use arbitrary::{Arbitrary, Unstructured};
15238 let mut buf = [0u8; 1024];
15239 rng.fill_bytes(&mut buf);
15240 let mut unstructured = Unstructured::new(&buf);
15241 Self::arbitrary(&mut unstructured).unwrap_or_default()
15242 }
15243}
15244impl Default for GLOBAL_POSITION_INT_DATA {
15245 fn default() -> Self {
15246 Self::DEFAULT.clone()
15247 }
15248}
15249impl MessageData for GLOBAL_POSITION_INT_DATA {
15250 type Message = MavMessage;
15251 const ID: u32 = 33u32;
15252 const NAME: &'static str = "GLOBAL_POSITION_INT";
15253 const EXTRA_CRC: u8 = 104u8;
15254 const ENCODED_LEN: usize = 28usize;
15255 fn deser(
15256 _version: MavlinkVersion,
15257 __input: &[u8],
15258 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15259 let avail_len = __input.len();
15260 let mut payload_buf = [0; Self::ENCODED_LEN];
15261 let mut buf = if avail_len < Self::ENCODED_LEN {
15262 payload_buf[0..avail_len].copy_from_slice(__input);
15263 Bytes::new(&payload_buf)
15264 } else {
15265 Bytes::new(__input)
15266 };
15267 let mut __struct = Self::default();
15268 __struct.time_boot_ms = buf.get_u32_le();
15269 __struct.lat = buf.get_i32_le();
15270 __struct.lon = buf.get_i32_le();
15271 __struct.alt = buf.get_i32_le();
15272 __struct.relative_alt = buf.get_i32_le();
15273 __struct.vx = buf.get_i16_le();
15274 __struct.vy = buf.get_i16_le();
15275 __struct.vz = buf.get_i16_le();
15276 __struct.hdg = buf.get_u16_le();
15277 Ok(__struct)
15278 }
15279 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15280 let mut __tmp = BytesMut::new(bytes);
15281 #[allow(clippy::absurd_extreme_comparisons)]
15282 #[allow(unused_comparisons)]
15283 if __tmp.remaining() < Self::ENCODED_LEN {
15284 panic!(
15285 "buffer is too small (need {} bytes, but got {})",
15286 Self::ENCODED_LEN,
15287 __tmp.remaining(),
15288 )
15289 }
15290 __tmp.put_u32_le(self.time_boot_ms);
15291 __tmp.put_i32_le(self.lat);
15292 __tmp.put_i32_le(self.lon);
15293 __tmp.put_i32_le(self.alt);
15294 __tmp.put_i32_le(self.relative_alt);
15295 __tmp.put_i16_le(self.vx);
15296 __tmp.put_i16_le(self.vy);
15297 __tmp.put_i16_le(self.vz);
15298 __tmp.put_u16_le(self.hdg);
15299 if matches!(version, MavlinkVersion::V2) {
15300 let len = __tmp.len();
15301 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15302 } else {
15303 __tmp.len()
15304 }
15305 }
15306}
15307#[doc = "id: 136"]
15308#[doc = "Streamed from drone to report progress of terrain map download (initiated by TERRAIN_REQUEST), or sent as a response to a TERRAIN_CHECK request. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
15309#[derive(Debug, Clone, PartialEq)]
15310#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15311#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15312pub struct TERRAIN_REPORT_DATA {
15313 #[doc = "Latitude"]
15314 pub lat: i32,
15315 #[doc = "Longitude"]
15316 pub lon: i32,
15317 #[doc = "Terrain height MSL"]
15318 pub terrain_height: f32,
15319 #[doc = "Current vehicle height above lat/lon terrain height"]
15320 pub current_height: f32,
15321 #[doc = "grid spacing (zero if terrain at this location unavailable)"]
15322 pub spacing: u16,
15323 #[doc = "Number of 4x4 terrain blocks waiting to be received or read from disk"]
15324 pub pending: u16,
15325 #[doc = "Number of 4x4 terrain blocks in memory"]
15326 pub loaded: u16,
15327}
15328impl TERRAIN_REPORT_DATA {
15329 pub const ENCODED_LEN: usize = 22usize;
15330 pub const DEFAULT: Self = Self {
15331 lat: 0_i32,
15332 lon: 0_i32,
15333 terrain_height: 0.0_f32,
15334 current_height: 0.0_f32,
15335 spacing: 0_u16,
15336 pending: 0_u16,
15337 loaded: 0_u16,
15338 };
15339 #[cfg(feature = "arbitrary")]
15340 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15341 use arbitrary::{Arbitrary, Unstructured};
15342 let mut buf = [0u8; 1024];
15343 rng.fill_bytes(&mut buf);
15344 let mut unstructured = Unstructured::new(&buf);
15345 Self::arbitrary(&mut unstructured).unwrap_or_default()
15346 }
15347}
15348impl Default for TERRAIN_REPORT_DATA {
15349 fn default() -> Self {
15350 Self::DEFAULT.clone()
15351 }
15352}
15353impl MessageData for TERRAIN_REPORT_DATA {
15354 type Message = MavMessage;
15355 const ID: u32 = 136u32;
15356 const NAME: &'static str = "TERRAIN_REPORT";
15357 const EXTRA_CRC: u8 = 1u8;
15358 const ENCODED_LEN: usize = 22usize;
15359 fn deser(
15360 _version: MavlinkVersion,
15361 __input: &[u8],
15362 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15363 let avail_len = __input.len();
15364 let mut payload_buf = [0; Self::ENCODED_LEN];
15365 let mut buf = if avail_len < Self::ENCODED_LEN {
15366 payload_buf[0..avail_len].copy_from_slice(__input);
15367 Bytes::new(&payload_buf)
15368 } else {
15369 Bytes::new(__input)
15370 };
15371 let mut __struct = Self::default();
15372 __struct.lat = buf.get_i32_le();
15373 __struct.lon = buf.get_i32_le();
15374 __struct.terrain_height = buf.get_f32_le();
15375 __struct.current_height = buf.get_f32_le();
15376 __struct.spacing = buf.get_u16_le();
15377 __struct.pending = buf.get_u16_le();
15378 __struct.loaded = buf.get_u16_le();
15379 Ok(__struct)
15380 }
15381 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15382 let mut __tmp = BytesMut::new(bytes);
15383 #[allow(clippy::absurd_extreme_comparisons)]
15384 #[allow(unused_comparisons)]
15385 if __tmp.remaining() < Self::ENCODED_LEN {
15386 panic!(
15387 "buffer is too small (need {} bytes, but got {})",
15388 Self::ENCODED_LEN,
15389 __tmp.remaining(),
15390 )
15391 }
15392 __tmp.put_i32_le(self.lat);
15393 __tmp.put_i32_le(self.lon);
15394 __tmp.put_f32_le(self.terrain_height);
15395 __tmp.put_f32_le(self.current_height);
15396 __tmp.put_u16_le(self.spacing);
15397 __tmp.put_u16_le(self.pending);
15398 __tmp.put_u16_le(self.loaded);
15399 if matches!(version, MavlinkVersion::V2) {
15400 let len = __tmp.len();
15401 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15402 } else {
15403 __tmp.len()
15404 }
15405 }
15406}
15407#[doc = "id: 54"]
15408#[doc = "Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations."]
15409#[derive(Debug, Clone, PartialEq)]
15410#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15411#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15412pub struct SAFETY_SET_ALLOWED_AREA_DATA {
15413 #[doc = "x position 1 / Latitude 1"]
15414 pub p1x: f32,
15415 #[doc = "y position 1 / Longitude 1"]
15416 pub p1y: f32,
15417 #[doc = "z position 1 / Altitude 1"]
15418 pub p1z: f32,
15419 #[doc = "x position 2 / Latitude 2"]
15420 pub p2x: f32,
15421 #[doc = "y position 2 / Longitude 2"]
15422 pub p2y: f32,
15423 #[doc = "z position 2 / Altitude 2"]
15424 pub p2z: f32,
15425 #[doc = "System ID"]
15426 pub target_system: u8,
15427 #[doc = "Component ID"]
15428 pub target_component: u8,
15429 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
15430 pub frame: MavFrame,
15431}
15432impl SAFETY_SET_ALLOWED_AREA_DATA {
15433 pub const ENCODED_LEN: usize = 27usize;
15434 pub const DEFAULT: Self = Self {
15435 p1x: 0.0_f32,
15436 p1y: 0.0_f32,
15437 p1z: 0.0_f32,
15438 p2x: 0.0_f32,
15439 p2y: 0.0_f32,
15440 p2z: 0.0_f32,
15441 target_system: 0_u8,
15442 target_component: 0_u8,
15443 frame: MavFrame::DEFAULT,
15444 };
15445 #[cfg(feature = "arbitrary")]
15446 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15447 use arbitrary::{Arbitrary, Unstructured};
15448 let mut buf = [0u8; 1024];
15449 rng.fill_bytes(&mut buf);
15450 let mut unstructured = Unstructured::new(&buf);
15451 Self::arbitrary(&mut unstructured).unwrap_or_default()
15452 }
15453}
15454impl Default for SAFETY_SET_ALLOWED_AREA_DATA {
15455 fn default() -> Self {
15456 Self::DEFAULT.clone()
15457 }
15458}
15459impl MessageData for SAFETY_SET_ALLOWED_AREA_DATA {
15460 type Message = MavMessage;
15461 const ID: u32 = 54u32;
15462 const NAME: &'static str = "SAFETY_SET_ALLOWED_AREA";
15463 const EXTRA_CRC: u8 = 15u8;
15464 const ENCODED_LEN: usize = 27usize;
15465 fn deser(
15466 _version: MavlinkVersion,
15467 __input: &[u8],
15468 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15469 let avail_len = __input.len();
15470 let mut payload_buf = [0; Self::ENCODED_LEN];
15471 let mut buf = if avail_len < Self::ENCODED_LEN {
15472 payload_buf[0..avail_len].copy_from_slice(__input);
15473 Bytes::new(&payload_buf)
15474 } else {
15475 Bytes::new(__input)
15476 };
15477 let mut __struct = Self::default();
15478 __struct.p1x = buf.get_f32_le();
15479 __struct.p1y = buf.get_f32_le();
15480 __struct.p1z = buf.get_f32_le();
15481 __struct.p2x = buf.get_f32_le();
15482 __struct.p2y = buf.get_f32_le();
15483 __struct.p2z = buf.get_f32_le();
15484 __struct.target_system = buf.get_u8();
15485 __struct.target_component = buf.get_u8();
15486 let tmp = buf.get_u8();
15487 __struct.frame =
15488 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15489 enum_type: "MavFrame",
15490 value: tmp as u32,
15491 })?;
15492 Ok(__struct)
15493 }
15494 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15495 let mut __tmp = BytesMut::new(bytes);
15496 #[allow(clippy::absurd_extreme_comparisons)]
15497 #[allow(unused_comparisons)]
15498 if __tmp.remaining() < Self::ENCODED_LEN {
15499 panic!(
15500 "buffer is too small (need {} bytes, but got {})",
15501 Self::ENCODED_LEN,
15502 __tmp.remaining(),
15503 )
15504 }
15505 __tmp.put_f32_le(self.p1x);
15506 __tmp.put_f32_le(self.p1y);
15507 __tmp.put_f32_le(self.p1z);
15508 __tmp.put_f32_le(self.p2x);
15509 __tmp.put_f32_le(self.p2y);
15510 __tmp.put_f32_le(self.p2z);
15511 __tmp.put_u8(self.target_system);
15512 __tmp.put_u8(self.target_component);
15513 __tmp.put_u8(self.frame as u8);
15514 if matches!(version, MavlinkVersion::V2) {
15515 let len = __tmp.len();
15516 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15517 } else {
15518 __tmp.len()
15519 }
15520 }
15521}
15522#[doc = "id: 243"]
15523#[doc = "Sets the home position. \tThe home position is the default position that the system will return to and land on. The position is set automatically by the system during the takeoff (and may also be set using this message). The global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. Under normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. The approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: the current home position may be emitted in a HOME_POSITION message on request (using MAV_CMD_REQUEST_MESSAGE with param1=242)."]
15524#[derive(Debug, Clone, PartialEq)]
15525#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15526#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15527pub struct SET_HOME_POSITION_DATA {
15528 #[doc = "Latitude (WGS84)"]
15529 pub latitude: i32,
15530 #[doc = "Longitude (WGS84)"]
15531 pub longitude: i32,
15532 #[doc = "Altitude (MSL). Positive for up."]
15533 pub altitude: i32,
15534 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
15535 pub x: f32,
15536 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
15537 pub y: f32,
15538 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
15539 pub z: f32,
15540 #[doc = "World to surface normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground"]
15541 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15542 pub q: [f32; 4],
15543 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
15544 pub approach_x: f32,
15545 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
15546 pub approach_y: f32,
15547 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
15548 pub approach_z: f32,
15549 #[doc = "System ID."]
15550 pub target_system: u8,
15551 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
15552 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15553 pub time_usec: u64,
15554}
15555impl SET_HOME_POSITION_DATA {
15556 pub const ENCODED_LEN: usize = 61usize;
15557 pub const DEFAULT: Self = Self {
15558 latitude: 0_i32,
15559 longitude: 0_i32,
15560 altitude: 0_i32,
15561 x: 0.0_f32,
15562 y: 0.0_f32,
15563 z: 0.0_f32,
15564 q: [0.0_f32; 4usize],
15565 approach_x: 0.0_f32,
15566 approach_y: 0.0_f32,
15567 approach_z: 0.0_f32,
15568 target_system: 0_u8,
15569 time_usec: 0_u64,
15570 };
15571 #[cfg(feature = "arbitrary")]
15572 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15573 use arbitrary::{Arbitrary, Unstructured};
15574 let mut buf = [0u8; 1024];
15575 rng.fill_bytes(&mut buf);
15576 let mut unstructured = Unstructured::new(&buf);
15577 Self::arbitrary(&mut unstructured).unwrap_or_default()
15578 }
15579}
15580impl Default for SET_HOME_POSITION_DATA {
15581 fn default() -> Self {
15582 Self::DEFAULT.clone()
15583 }
15584}
15585impl MessageData for SET_HOME_POSITION_DATA {
15586 type Message = MavMessage;
15587 const ID: u32 = 243u32;
15588 const NAME: &'static str = "SET_HOME_POSITION";
15589 const EXTRA_CRC: u8 = 85u8;
15590 const ENCODED_LEN: usize = 61usize;
15591 fn deser(
15592 _version: MavlinkVersion,
15593 __input: &[u8],
15594 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15595 let avail_len = __input.len();
15596 let mut payload_buf = [0; Self::ENCODED_LEN];
15597 let mut buf = if avail_len < Self::ENCODED_LEN {
15598 payload_buf[0..avail_len].copy_from_slice(__input);
15599 Bytes::new(&payload_buf)
15600 } else {
15601 Bytes::new(__input)
15602 };
15603 let mut __struct = Self::default();
15604 __struct.latitude = buf.get_i32_le();
15605 __struct.longitude = buf.get_i32_le();
15606 __struct.altitude = buf.get_i32_le();
15607 __struct.x = buf.get_f32_le();
15608 __struct.y = buf.get_f32_le();
15609 __struct.z = buf.get_f32_le();
15610 for v in &mut __struct.q {
15611 let val = buf.get_f32_le();
15612 *v = val;
15613 }
15614 __struct.approach_x = buf.get_f32_le();
15615 __struct.approach_y = buf.get_f32_le();
15616 __struct.approach_z = buf.get_f32_le();
15617 __struct.target_system = buf.get_u8();
15618 __struct.time_usec = buf.get_u64_le();
15619 Ok(__struct)
15620 }
15621 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15622 let mut __tmp = BytesMut::new(bytes);
15623 #[allow(clippy::absurd_extreme_comparisons)]
15624 #[allow(unused_comparisons)]
15625 if __tmp.remaining() < Self::ENCODED_LEN {
15626 panic!(
15627 "buffer is too small (need {} bytes, but got {})",
15628 Self::ENCODED_LEN,
15629 __tmp.remaining(),
15630 )
15631 }
15632 __tmp.put_i32_le(self.latitude);
15633 __tmp.put_i32_le(self.longitude);
15634 __tmp.put_i32_le(self.altitude);
15635 __tmp.put_f32_le(self.x);
15636 __tmp.put_f32_le(self.y);
15637 __tmp.put_f32_le(self.z);
15638 for val in &self.q {
15639 __tmp.put_f32_le(*val);
15640 }
15641 __tmp.put_f32_le(self.approach_x);
15642 __tmp.put_f32_le(self.approach_y);
15643 __tmp.put_f32_le(self.approach_z);
15644 __tmp.put_u8(self.target_system);
15645 __tmp.put_u64_le(self.time_usec);
15646 if matches!(version, MavlinkVersion::V2) {
15647 let len = __tmp.len();
15648 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15649 } else {
15650 __tmp.len()
15651 }
15652 }
15653}
15654#[doc = "id: 148"]
15655#[doc = "Version and capability of autopilot software. This should be emitted in response to a request with MAV_CMD_REQUEST_MESSAGE."]
15656#[derive(Debug, Clone, PartialEq)]
15657#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15658#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15659pub struct AUTOPILOT_VERSION_DATA {
15660 #[doc = "Bitmap of capabilities"]
15661 pub capabilities: MavProtocolCapability,
15662 #[doc = "UID if provided by hardware (see uid2)"]
15663 pub uid: u64,
15664 #[doc = "Firmware version number. The field must be encoded as 4 bytes, where each byte (shown from MSB to LSB) is part of a semantic version: (major) (minor) (patch) (FIRMWARE_VERSION_TYPE)."]
15665 pub flight_sw_version: u32,
15666 #[doc = "Middleware version number"]
15667 pub middleware_sw_version: u32,
15668 #[doc = "Operating system version number"]
15669 pub os_sw_version: u32,
15670 #[doc = "HW / board version (last 8 bits should be silicon ID, if any). The first 16 bits of this field specify <https://github.com/PX4/PX4-Bootloader/blob/master/board_types.txt>"]
15671 pub board_version: u32,
15672 #[doc = "ID of the board vendor"]
15673 pub vendor_id: u16,
15674 #[doc = "ID of the product"]
15675 pub product_id: u16,
15676 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
15677 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15678 pub flight_custom_version: [u8; 8],
15679 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
15680 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15681 pub middleware_custom_version: [u8; 8],
15682 #[doc = "Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases."]
15683 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15684 pub os_custom_version: [u8; 8],
15685 #[doc = "UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)"]
15686 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
15687 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15688 pub uid2: [u8; 18],
15689}
15690impl AUTOPILOT_VERSION_DATA {
15691 pub const ENCODED_LEN: usize = 78usize;
15692 pub const DEFAULT: Self = Self {
15693 capabilities: MavProtocolCapability::DEFAULT,
15694 uid: 0_u64,
15695 flight_sw_version: 0_u32,
15696 middleware_sw_version: 0_u32,
15697 os_sw_version: 0_u32,
15698 board_version: 0_u32,
15699 vendor_id: 0_u16,
15700 product_id: 0_u16,
15701 flight_custom_version: [0_u8; 8usize],
15702 middleware_custom_version: [0_u8; 8usize],
15703 os_custom_version: [0_u8; 8usize],
15704 uid2: [0_u8; 18usize],
15705 };
15706 #[cfg(feature = "arbitrary")]
15707 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15708 use arbitrary::{Arbitrary, Unstructured};
15709 let mut buf = [0u8; 1024];
15710 rng.fill_bytes(&mut buf);
15711 let mut unstructured = Unstructured::new(&buf);
15712 Self::arbitrary(&mut unstructured).unwrap_or_default()
15713 }
15714}
15715impl Default for AUTOPILOT_VERSION_DATA {
15716 fn default() -> Self {
15717 Self::DEFAULT.clone()
15718 }
15719}
15720impl MessageData for AUTOPILOT_VERSION_DATA {
15721 type Message = MavMessage;
15722 const ID: u32 = 148u32;
15723 const NAME: &'static str = "AUTOPILOT_VERSION";
15724 const EXTRA_CRC: u8 = 178u8;
15725 const ENCODED_LEN: usize = 78usize;
15726 fn deser(
15727 _version: MavlinkVersion,
15728 __input: &[u8],
15729 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15730 let avail_len = __input.len();
15731 let mut payload_buf = [0; Self::ENCODED_LEN];
15732 let mut buf = if avail_len < Self::ENCODED_LEN {
15733 payload_buf[0..avail_len].copy_from_slice(__input);
15734 Bytes::new(&payload_buf)
15735 } else {
15736 Bytes::new(__input)
15737 };
15738 let mut __struct = Self::default();
15739 let tmp = buf.get_u64_le();
15740 __struct.capabilities = MavProtocolCapability::from_bits(
15741 tmp & MavProtocolCapability::all().bits(),
15742 )
15743 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15744 flag_type: "MavProtocolCapability",
15745 value: tmp as u32,
15746 })?;
15747 __struct.uid = buf.get_u64_le();
15748 __struct.flight_sw_version = buf.get_u32_le();
15749 __struct.middleware_sw_version = buf.get_u32_le();
15750 __struct.os_sw_version = buf.get_u32_le();
15751 __struct.board_version = buf.get_u32_le();
15752 __struct.vendor_id = buf.get_u16_le();
15753 __struct.product_id = buf.get_u16_le();
15754 for v in &mut __struct.flight_custom_version {
15755 let val = buf.get_u8();
15756 *v = val;
15757 }
15758 for v in &mut __struct.middleware_custom_version {
15759 let val = buf.get_u8();
15760 *v = val;
15761 }
15762 for v in &mut __struct.os_custom_version {
15763 let val = buf.get_u8();
15764 *v = val;
15765 }
15766 for v in &mut __struct.uid2 {
15767 let val = buf.get_u8();
15768 *v = val;
15769 }
15770 Ok(__struct)
15771 }
15772 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15773 let mut __tmp = BytesMut::new(bytes);
15774 #[allow(clippy::absurd_extreme_comparisons)]
15775 #[allow(unused_comparisons)]
15776 if __tmp.remaining() < Self::ENCODED_LEN {
15777 panic!(
15778 "buffer is too small (need {} bytes, but got {})",
15779 Self::ENCODED_LEN,
15780 __tmp.remaining(),
15781 )
15782 }
15783 __tmp.put_u64_le(self.capabilities.bits());
15784 __tmp.put_u64_le(self.uid);
15785 __tmp.put_u32_le(self.flight_sw_version);
15786 __tmp.put_u32_le(self.middleware_sw_version);
15787 __tmp.put_u32_le(self.os_sw_version);
15788 __tmp.put_u32_le(self.board_version);
15789 __tmp.put_u16_le(self.vendor_id);
15790 __tmp.put_u16_le(self.product_id);
15791 for val in &self.flight_custom_version {
15792 __tmp.put_u8(*val);
15793 }
15794 for val in &self.middleware_custom_version {
15795 __tmp.put_u8(*val);
15796 }
15797 for val in &self.os_custom_version {
15798 __tmp.put_u8(*val);
15799 }
15800 for val in &self.uid2 {
15801 __tmp.put_u8(*val);
15802 }
15803 if matches!(version, MavlinkVersion::V2) {
15804 let len = __tmp.len();
15805 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15806 } else {
15807 __tmp.len()
15808 }
15809 }
15810}
15811#[doc = "id: 256"]
15812#[doc = "Setup a MAVLink2 signing key. If called with secret_key of all zero and zero initial_timestamp will disable signing."]
15813#[derive(Debug, Clone, PartialEq)]
15814#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15815#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15816pub struct SETUP_SIGNING_DATA {
15817 #[doc = "initial timestamp"]
15818 pub initial_timestamp: u64,
15819 #[doc = "system id of the target"]
15820 pub target_system: u8,
15821 #[doc = "component ID of the target"]
15822 pub target_component: u8,
15823 #[doc = "signing key"]
15824 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
15825 pub secret_key: [u8; 32],
15826}
15827impl SETUP_SIGNING_DATA {
15828 pub const ENCODED_LEN: usize = 42usize;
15829 pub const DEFAULT: Self = Self {
15830 initial_timestamp: 0_u64,
15831 target_system: 0_u8,
15832 target_component: 0_u8,
15833 secret_key: [0_u8; 32usize],
15834 };
15835 #[cfg(feature = "arbitrary")]
15836 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15837 use arbitrary::{Arbitrary, Unstructured};
15838 let mut buf = [0u8; 1024];
15839 rng.fill_bytes(&mut buf);
15840 let mut unstructured = Unstructured::new(&buf);
15841 Self::arbitrary(&mut unstructured).unwrap_or_default()
15842 }
15843}
15844impl Default for SETUP_SIGNING_DATA {
15845 fn default() -> Self {
15846 Self::DEFAULT.clone()
15847 }
15848}
15849impl MessageData for SETUP_SIGNING_DATA {
15850 type Message = MavMessage;
15851 const ID: u32 = 256u32;
15852 const NAME: &'static str = "SETUP_SIGNING";
15853 const EXTRA_CRC: u8 = 71u8;
15854 const ENCODED_LEN: usize = 42usize;
15855 fn deser(
15856 _version: MavlinkVersion,
15857 __input: &[u8],
15858 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15859 let avail_len = __input.len();
15860 let mut payload_buf = [0; Self::ENCODED_LEN];
15861 let mut buf = if avail_len < Self::ENCODED_LEN {
15862 payload_buf[0..avail_len].copy_from_slice(__input);
15863 Bytes::new(&payload_buf)
15864 } else {
15865 Bytes::new(__input)
15866 };
15867 let mut __struct = Self::default();
15868 __struct.initial_timestamp = buf.get_u64_le();
15869 __struct.target_system = buf.get_u8();
15870 __struct.target_component = buf.get_u8();
15871 for v in &mut __struct.secret_key {
15872 let val = buf.get_u8();
15873 *v = val;
15874 }
15875 Ok(__struct)
15876 }
15877 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
15878 let mut __tmp = BytesMut::new(bytes);
15879 #[allow(clippy::absurd_extreme_comparisons)]
15880 #[allow(unused_comparisons)]
15881 if __tmp.remaining() < Self::ENCODED_LEN {
15882 panic!(
15883 "buffer is too small (need {} bytes, but got {})",
15884 Self::ENCODED_LEN,
15885 __tmp.remaining(),
15886 )
15887 }
15888 __tmp.put_u64_le(self.initial_timestamp);
15889 __tmp.put_u8(self.target_system);
15890 __tmp.put_u8(self.target_component);
15891 for val in &self.secret_key {
15892 __tmp.put_u8(*val);
15893 }
15894 if matches!(version, MavlinkVersion::V2) {
15895 let len = __tmp.len();
15896 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
15897 } else {
15898 __tmp.len()
15899 }
15900 }
15901}
15902#[doc = "id: 440"]
15903#[doc = "Illuminator status."]
15904#[derive(Debug, Clone, PartialEq)]
15905#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
15906#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
15907pub struct ILLUMINATOR_STATUS_DATA {
15908 #[doc = "Time since the start-up of the illuminator in ms"]
15909 pub uptime_ms: u32,
15910 #[doc = "Errors"]
15911 pub error_status: IlluminatorErrorFlags,
15912 #[doc = "Illuminator brightness"]
15913 pub brightness: f32,
15914 #[doc = "Illuminator strobing period in seconds"]
15915 pub strobe_period: f32,
15916 #[doc = "Illuminator strobing duty cycle"]
15917 pub strobe_duty_cycle: f32,
15918 #[doc = "Temperature in Celsius"]
15919 pub temp_c: f32,
15920 #[doc = "Minimum strobing period in seconds"]
15921 pub min_strobe_period: f32,
15922 #[doc = "Maximum strobing period in seconds"]
15923 pub max_strobe_period: f32,
15924 #[doc = "0: Illuminators OFF, 1: Illuminators ON"]
15925 pub enable: u8,
15926 #[doc = "Supported illuminator modes"]
15927 pub mode_bitmask: IlluminatorMode,
15928 #[doc = "Illuminator mode"]
15929 pub mode: IlluminatorMode,
15930}
15931impl ILLUMINATOR_STATUS_DATA {
15932 pub const ENCODED_LEN: usize = 35usize;
15933 pub const DEFAULT: Self = Self {
15934 uptime_ms: 0_u32,
15935 error_status: IlluminatorErrorFlags::DEFAULT,
15936 brightness: 0.0_f32,
15937 strobe_period: 0.0_f32,
15938 strobe_duty_cycle: 0.0_f32,
15939 temp_c: 0.0_f32,
15940 min_strobe_period: 0.0_f32,
15941 max_strobe_period: 0.0_f32,
15942 enable: 0_u8,
15943 mode_bitmask: IlluminatorMode::DEFAULT,
15944 mode: IlluminatorMode::DEFAULT,
15945 };
15946 #[cfg(feature = "arbitrary")]
15947 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
15948 use arbitrary::{Arbitrary, Unstructured};
15949 let mut buf = [0u8; 1024];
15950 rng.fill_bytes(&mut buf);
15951 let mut unstructured = Unstructured::new(&buf);
15952 Self::arbitrary(&mut unstructured).unwrap_or_default()
15953 }
15954}
15955impl Default for ILLUMINATOR_STATUS_DATA {
15956 fn default() -> Self {
15957 Self::DEFAULT.clone()
15958 }
15959}
15960impl MessageData for ILLUMINATOR_STATUS_DATA {
15961 type Message = MavMessage;
15962 const ID: u32 = 440u32;
15963 const NAME: &'static str = "ILLUMINATOR_STATUS";
15964 const EXTRA_CRC: u8 = 66u8;
15965 const ENCODED_LEN: usize = 35usize;
15966 fn deser(
15967 _version: MavlinkVersion,
15968 __input: &[u8],
15969 ) -> Result<Self, ::mavlink_core::error::ParserError> {
15970 let avail_len = __input.len();
15971 let mut payload_buf = [0; Self::ENCODED_LEN];
15972 let mut buf = if avail_len < Self::ENCODED_LEN {
15973 payload_buf[0..avail_len].copy_from_slice(__input);
15974 Bytes::new(&payload_buf)
15975 } else {
15976 Bytes::new(__input)
15977 };
15978 let mut __struct = Self::default();
15979 __struct.uptime_ms = buf.get_u32_le();
15980 let tmp = buf.get_u32_le();
15981 __struct.error_status = IlluminatorErrorFlags::from_bits(
15982 tmp & IlluminatorErrorFlags::all().bits(),
15983 )
15984 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
15985 flag_type: "IlluminatorErrorFlags",
15986 value: tmp as u32,
15987 })?;
15988 __struct.brightness = buf.get_f32_le();
15989 __struct.strobe_period = buf.get_f32_le();
15990 __struct.strobe_duty_cycle = buf.get_f32_le();
15991 __struct.temp_c = buf.get_f32_le();
15992 __struct.min_strobe_period = buf.get_f32_le();
15993 __struct.max_strobe_period = buf.get_f32_le();
15994 __struct.enable = buf.get_u8();
15995 let tmp = buf.get_u8();
15996 __struct.mode_bitmask =
15997 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
15998 enum_type: "IlluminatorMode",
15999 value: tmp as u32,
16000 })?;
16001 let tmp = buf.get_u8();
16002 __struct.mode =
16003 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16004 enum_type: "IlluminatorMode",
16005 value: tmp as u32,
16006 })?;
16007 Ok(__struct)
16008 }
16009 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16010 let mut __tmp = BytesMut::new(bytes);
16011 #[allow(clippy::absurd_extreme_comparisons)]
16012 #[allow(unused_comparisons)]
16013 if __tmp.remaining() < Self::ENCODED_LEN {
16014 panic!(
16015 "buffer is too small (need {} bytes, but got {})",
16016 Self::ENCODED_LEN,
16017 __tmp.remaining(),
16018 )
16019 }
16020 __tmp.put_u32_le(self.uptime_ms);
16021 __tmp.put_u32_le(self.error_status.bits());
16022 __tmp.put_f32_le(self.brightness);
16023 __tmp.put_f32_le(self.strobe_period);
16024 __tmp.put_f32_le(self.strobe_duty_cycle);
16025 __tmp.put_f32_le(self.temp_c);
16026 __tmp.put_f32_le(self.min_strobe_period);
16027 __tmp.put_f32_le(self.max_strobe_period);
16028 __tmp.put_u8(self.enable);
16029 __tmp.put_u8(self.mode_bitmask as u8);
16030 __tmp.put_u8(self.mode as u8);
16031 if matches!(version, MavlinkVersion::V2) {
16032 let len = __tmp.len();
16033 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16034 } else {
16035 __tmp.len()
16036 }
16037 }
16038}
16039#[doc = "id: 311"]
16040#[doc = "General information describing a particular UAVCAN node. Please refer to the definition of the UAVCAN service \"uavcan.protocol.GetNodeInfo\" for the background information. This message should be emitted by the system whenever a new node appears online, or an existing node reboots. Additionally, it can be emitted upon request from the other end of the MAVLink channel (see MAV_CMD_UAVCAN_GET_NODE_INFO). It is also not prohibited to emit this message unconditionally at a low frequency. The UAVCAN specification is available at <http://uavcan.org>."]
16041#[derive(Debug, Clone, PartialEq)]
16042#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16043#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16044pub struct UAVCAN_NODE_INFO_DATA {
16045 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
16046 pub time_usec: u64,
16047 #[doc = "Time since the start-up of the node."]
16048 pub uptime_sec: u32,
16049 #[doc = "Version control system (VCS) revision identifier (e.g. git short commit hash). 0 if unknown."]
16050 pub sw_vcs_commit: u32,
16051 #[doc = "Node name string. For example, \"sapog.px4.io\"."]
16052 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16053 pub name: [u8; 80],
16054 #[doc = "Hardware major version number."]
16055 pub hw_version_major: u8,
16056 #[doc = "Hardware minor version number."]
16057 pub hw_version_minor: u8,
16058 #[doc = "Hardware unique 128-bit ID."]
16059 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16060 pub hw_unique_id: [u8; 16],
16061 #[doc = "Software major version number."]
16062 pub sw_version_major: u8,
16063 #[doc = "Software minor version number."]
16064 pub sw_version_minor: u8,
16065}
16066impl UAVCAN_NODE_INFO_DATA {
16067 pub const ENCODED_LEN: usize = 116usize;
16068 pub const DEFAULT: Self = Self {
16069 time_usec: 0_u64,
16070 uptime_sec: 0_u32,
16071 sw_vcs_commit: 0_u32,
16072 name: [0_u8; 80usize],
16073 hw_version_major: 0_u8,
16074 hw_version_minor: 0_u8,
16075 hw_unique_id: [0_u8; 16usize],
16076 sw_version_major: 0_u8,
16077 sw_version_minor: 0_u8,
16078 };
16079 #[cfg(feature = "arbitrary")]
16080 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16081 use arbitrary::{Arbitrary, Unstructured};
16082 let mut buf = [0u8; 1024];
16083 rng.fill_bytes(&mut buf);
16084 let mut unstructured = Unstructured::new(&buf);
16085 Self::arbitrary(&mut unstructured).unwrap_or_default()
16086 }
16087}
16088impl Default for UAVCAN_NODE_INFO_DATA {
16089 fn default() -> Self {
16090 Self::DEFAULT.clone()
16091 }
16092}
16093impl MessageData for UAVCAN_NODE_INFO_DATA {
16094 type Message = MavMessage;
16095 const ID: u32 = 311u32;
16096 const NAME: &'static str = "UAVCAN_NODE_INFO";
16097 const EXTRA_CRC: u8 = 95u8;
16098 const ENCODED_LEN: usize = 116usize;
16099 fn deser(
16100 _version: MavlinkVersion,
16101 __input: &[u8],
16102 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16103 let avail_len = __input.len();
16104 let mut payload_buf = [0; Self::ENCODED_LEN];
16105 let mut buf = if avail_len < Self::ENCODED_LEN {
16106 payload_buf[0..avail_len].copy_from_slice(__input);
16107 Bytes::new(&payload_buf)
16108 } else {
16109 Bytes::new(__input)
16110 };
16111 let mut __struct = Self::default();
16112 __struct.time_usec = buf.get_u64_le();
16113 __struct.uptime_sec = buf.get_u32_le();
16114 __struct.sw_vcs_commit = buf.get_u32_le();
16115 for v in &mut __struct.name {
16116 let val = buf.get_u8();
16117 *v = val;
16118 }
16119 __struct.hw_version_major = buf.get_u8();
16120 __struct.hw_version_minor = buf.get_u8();
16121 for v in &mut __struct.hw_unique_id {
16122 let val = buf.get_u8();
16123 *v = val;
16124 }
16125 __struct.sw_version_major = buf.get_u8();
16126 __struct.sw_version_minor = buf.get_u8();
16127 Ok(__struct)
16128 }
16129 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16130 let mut __tmp = BytesMut::new(bytes);
16131 #[allow(clippy::absurd_extreme_comparisons)]
16132 #[allow(unused_comparisons)]
16133 if __tmp.remaining() < Self::ENCODED_LEN {
16134 panic!(
16135 "buffer is too small (need {} bytes, but got {})",
16136 Self::ENCODED_LEN,
16137 __tmp.remaining(),
16138 )
16139 }
16140 __tmp.put_u64_le(self.time_usec);
16141 __tmp.put_u32_le(self.uptime_sec);
16142 __tmp.put_u32_le(self.sw_vcs_commit);
16143 for val in &self.name {
16144 __tmp.put_u8(*val);
16145 }
16146 __tmp.put_u8(self.hw_version_major);
16147 __tmp.put_u8(self.hw_version_minor);
16148 for val in &self.hw_unique_id {
16149 __tmp.put_u8(*val);
16150 }
16151 __tmp.put_u8(self.sw_version_major);
16152 __tmp.put_u8(self.sw_version_minor);
16153 if matches!(version, MavlinkVersion::V2) {
16154 let len = __tmp.len();
16155 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16156 } else {
16157 __tmp.len()
16158 }
16159 }
16160}
16161#[doc = "id: 283"]
16162#[doc = "Information about a low level gimbal. This message should be requested by the gimbal manager or a ground station using MAV_CMD_REQUEST_MESSAGE. The maximum angles and rates are the limits by hardware. However, the limits by software used are likely different/smaller and dependent on mode/settings/etc.."]
16163#[derive(Debug, Clone, PartialEq)]
16164#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16165#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16166pub struct GIMBAL_DEVICE_INFORMATION_DATA {
16167 #[doc = "UID of gimbal hardware (0 if unknown)."]
16168 pub uid: u64,
16169 #[doc = "Timestamp (time since system boot)."]
16170 pub time_boot_ms: u32,
16171 #[doc = "0xff)."]
16172 pub firmware_version: u32,
16173 #[doc = "0xff)."]
16174 pub hardware_version: u32,
16175 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
16176 pub roll_min: f32,
16177 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left). NAN if unknown."]
16178 pub roll_max: f32,
16179 #[doc = "Minimum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
16180 pub pitch_min: f32,
16181 #[doc = "Maximum hardware pitch angle (positive: up, negative: down). NAN if unknown."]
16182 pub pitch_max: f32,
16183 #[doc = "Minimum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
16184 pub yaw_min: f32,
16185 #[doc = "Maximum hardware yaw angle (positive: to the right, negative: to the left). NAN if unknown."]
16186 pub yaw_max: f32,
16187 #[doc = "Bitmap of gimbal capability flags."]
16188 pub cap_flags: GimbalDeviceCapFlags,
16189 #[doc = "Bitmap for use for gimbal-specific capability flags."]
16190 pub custom_cap_flags: u16,
16191 #[doc = "Name of the gimbal vendor."]
16192 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16193 pub vendor_name: [u8; 32],
16194 #[doc = "Name of the gimbal model."]
16195 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16196 pub model_name: [u8; 32],
16197 #[doc = "Custom name of the gimbal given to it by the user."]
16198 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16199 pub custom_name: [u8; 32],
16200 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set to a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
16201 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
16202 pub gimbal_device_id: u8,
16203}
16204impl GIMBAL_DEVICE_INFORMATION_DATA {
16205 pub const ENCODED_LEN: usize = 145usize;
16206 pub const DEFAULT: Self = Self {
16207 uid: 0_u64,
16208 time_boot_ms: 0_u32,
16209 firmware_version: 0_u32,
16210 hardware_version: 0_u32,
16211 roll_min: 0.0_f32,
16212 roll_max: 0.0_f32,
16213 pitch_min: 0.0_f32,
16214 pitch_max: 0.0_f32,
16215 yaw_min: 0.0_f32,
16216 yaw_max: 0.0_f32,
16217 cap_flags: GimbalDeviceCapFlags::DEFAULT,
16218 custom_cap_flags: 0_u16,
16219 vendor_name: [0_u8; 32usize],
16220 model_name: [0_u8; 32usize],
16221 custom_name: [0_u8; 32usize],
16222 gimbal_device_id: 0_u8,
16223 };
16224 #[cfg(feature = "arbitrary")]
16225 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16226 use arbitrary::{Arbitrary, Unstructured};
16227 let mut buf = [0u8; 1024];
16228 rng.fill_bytes(&mut buf);
16229 let mut unstructured = Unstructured::new(&buf);
16230 Self::arbitrary(&mut unstructured).unwrap_or_default()
16231 }
16232}
16233impl Default for GIMBAL_DEVICE_INFORMATION_DATA {
16234 fn default() -> Self {
16235 Self::DEFAULT.clone()
16236 }
16237}
16238impl MessageData for GIMBAL_DEVICE_INFORMATION_DATA {
16239 type Message = MavMessage;
16240 const ID: u32 = 283u32;
16241 const NAME: &'static str = "GIMBAL_DEVICE_INFORMATION";
16242 const EXTRA_CRC: u8 = 74u8;
16243 const ENCODED_LEN: usize = 145usize;
16244 fn deser(
16245 _version: MavlinkVersion,
16246 __input: &[u8],
16247 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16248 let avail_len = __input.len();
16249 let mut payload_buf = [0; Self::ENCODED_LEN];
16250 let mut buf = if avail_len < Self::ENCODED_LEN {
16251 payload_buf[0..avail_len].copy_from_slice(__input);
16252 Bytes::new(&payload_buf)
16253 } else {
16254 Bytes::new(__input)
16255 };
16256 let mut __struct = Self::default();
16257 __struct.uid = buf.get_u64_le();
16258 __struct.time_boot_ms = buf.get_u32_le();
16259 __struct.firmware_version = buf.get_u32_le();
16260 __struct.hardware_version = buf.get_u32_le();
16261 __struct.roll_min = buf.get_f32_le();
16262 __struct.roll_max = buf.get_f32_le();
16263 __struct.pitch_min = buf.get_f32_le();
16264 __struct.pitch_max = buf.get_f32_le();
16265 __struct.yaw_min = buf.get_f32_le();
16266 __struct.yaw_max = buf.get_f32_le();
16267 let tmp = buf.get_u16_le();
16268 __struct.cap_flags = GimbalDeviceCapFlags::from_bits(
16269 tmp & GimbalDeviceCapFlags::all().bits(),
16270 )
16271 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
16272 flag_type: "GimbalDeviceCapFlags",
16273 value: tmp as u32,
16274 })?;
16275 __struct.custom_cap_flags = buf.get_u16_le();
16276 for v in &mut __struct.vendor_name {
16277 let val = buf.get_u8();
16278 *v = val;
16279 }
16280 for v in &mut __struct.model_name {
16281 let val = buf.get_u8();
16282 *v = val;
16283 }
16284 for v in &mut __struct.custom_name {
16285 let val = buf.get_u8();
16286 *v = val;
16287 }
16288 __struct.gimbal_device_id = buf.get_u8();
16289 Ok(__struct)
16290 }
16291 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16292 let mut __tmp = BytesMut::new(bytes);
16293 #[allow(clippy::absurd_extreme_comparisons)]
16294 #[allow(unused_comparisons)]
16295 if __tmp.remaining() < Self::ENCODED_LEN {
16296 panic!(
16297 "buffer is too small (need {} bytes, but got {})",
16298 Self::ENCODED_LEN,
16299 __tmp.remaining(),
16300 )
16301 }
16302 __tmp.put_u64_le(self.uid);
16303 __tmp.put_u32_le(self.time_boot_ms);
16304 __tmp.put_u32_le(self.firmware_version);
16305 __tmp.put_u32_le(self.hardware_version);
16306 __tmp.put_f32_le(self.roll_min);
16307 __tmp.put_f32_le(self.roll_max);
16308 __tmp.put_f32_le(self.pitch_min);
16309 __tmp.put_f32_le(self.pitch_max);
16310 __tmp.put_f32_le(self.yaw_min);
16311 __tmp.put_f32_le(self.yaw_max);
16312 __tmp.put_u16_le(self.cap_flags.bits());
16313 __tmp.put_u16_le(self.custom_cap_flags);
16314 for val in &self.vendor_name {
16315 __tmp.put_u8(*val);
16316 }
16317 for val in &self.model_name {
16318 __tmp.put_u8(*val);
16319 }
16320 for val in &self.custom_name {
16321 __tmp.put_u8(*val);
16322 }
16323 __tmp.put_u8(self.gimbal_device_id);
16324 if matches!(version, MavlinkVersion::V2) {
16325 let len = __tmp.len();
16326 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16327 } else {
16328 __tmp.len()
16329 }
16330 }
16331}
16332#[doc = "id: 282"]
16333#[doc = "High level message to control a gimbal's attitude. This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
16334#[derive(Debug, Clone, PartialEq)]
16335#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16336#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16337pub struct GIMBAL_MANAGER_SET_ATTITUDE_DATA {
16338 #[doc = "High level gimbal manager flags to use."]
16339 pub flags: GimbalManagerFlags,
16340 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)"]
16341 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16342 pub q: [f32; 4],
16343 #[doc = "X component of angular velocity, positive is rolling to the right, NaN to be ignored."]
16344 pub angular_velocity_x: f32,
16345 #[doc = "Y component of angular velocity, positive is pitching up, NaN to be ignored."]
16346 pub angular_velocity_y: f32,
16347 #[doc = "Z component of angular velocity, positive is yawing to the right, NaN to be ignored."]
16348 pub angular_velocity_z: f32,
16349 #[doc = "System ID"]
16350 pub target_system: u8,
16351 #[doc = "Component ID"]
16352 pub target_component: u8,
16353 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
16354 pub gimbal_device_id: u8,
16355}
16356impl GIMBAL_MANAGER_SET_ATTITUDE_DATA {
16357 pub const ENCODED_LEN: usize = 35usize;
16358 pub const DEFAULT: Self = Self {
16359 flags: GimbalManagerFlags::DEFAULT,
16360 q: [0.0_f32; 4usize],
16361 angular_velocity_x: 0.0_f32,
16362 angular_velocity_y: 0.0_f32,
16363 angular_velocity_z: 0.0_f32,
16364 target_system: 0_u8,
16365 target_component: 0_u8,
16366 gimbal_device_id: 0_u8,
16367 };
16368 #[cfg(feature = "arbitrary")]
16369 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16370 use arbitrary::{Arbitrary, Unstructured};
16371 let mut buf = [0u8; 1024];
16372 rng.fill_bytes(&mut buf);
16373 let mut unstructured = Unstructured::new(&buf);
16374 Self::arbitrary(&mut unstructured).unwrap_or_default()
16375 }
16376}
16377impl Default for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
16378 fn default() -> Self {
16379 Self::DEFAULT.clone()
16380 }
16381}
16382impl MessageData for GIMBAL_MANAGER_SET_ATTITUDE_DATA {
16383 type Message = MavMessage;
16384 const ID: u32 = 282u32;
16385 const NAME: &'static str = "GIMBAL_MANAGER_SET_ATTITUDE";
16386 const EXTRA_CRC: u8 = 123u8;
16387 const ENCODED_LEN: usize = 35usize;
16388 fn deser(
16389 _version: MavlinkVersion,
16390 __input: &[u8],
16391 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16392 let avail_len = __input.len();
16393 let mut payload_buf = [0; Self::ENCODED_LEN];
16394 let mut buf = if avail_len < Self::ENCODED_LEN {
16395 payload_buf[0..avail_len].copy_from_slice(__input);
16396 Bytes::new(&payload_buf)
16397 } else {
16398 Bytes::new(__input)
16399 };
16400 let mut __struct = Self::default();
16401 let tmp = buf.get_u32_le();
16402 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
16403 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
16404 flag_type: "GimbalManagerFlags",
16405 value: tmp as u32,
16406 })?;
16407 for v in &mut __struct.q {
16408 let val = buf.get_f32_le();
16409 *v = val;
16410 }
16411 __struct.angular_velocity_x = buf.get_f32_le();
16412 __struct.angular_velocity_y = buf.get_f32_le();
16413 __struct.angular_velocity_z = buf.get_f32_le();
16414 __struct.target_system = buf.get_u8();
16415 __struct.target_component = buf.get_u8();
16416 __struct.gimbal_device_id = buf.get_u8();
16417 Ok(__struct)
16418 }
16419 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16420 let mut __tmp = BytesMut::new(bytes);
16421 #[allow(clippy::absurd_extreme_comparisons)]
16422 #[allow(unused_comparisons)]
16423 if __tmp.remaining() < Self::ENCODED_LEN {
16424 panic!(
16425 "buffer is too small (need {} bytes, but got {})",
16426 Self::ENCODED_LEN,
16427 __tmp.remaining(),
16428 )
16429 }
16430 __tmp.put_u32_le(self.flags.bits());
16431 for val in &self.q {
16432 __tmp.put_f32_le(*val);
16433 }
16434 __tmp.put_f32_le(self.angular_velocity_x);
16435 __tmp.put_f32_le(self.angular_velocity_y);
16436 __tmp.put_f32_le(self.angular_velocity_z);
16437 __tmp.put_u8(self.target_system);
16438 __tmp.put_u8(self.target_component);
16439 __tmp.put_u8(self.gimbal_device_id);
16440 if matches!(version, MavlinkVersion::V2) {
16441 let len = __tmp.len();
16442 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16443 } else {
16444 __tmp.len()
16445 }
16446 }
16447}
16448#[doc = "id: 267"]
16449#[doc = "A message containing logged data which requires a LOGGING_ACK to be sent back."]
16450#[derive(Debug, Clone, PartialEq)]
16451#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16452#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16453pub struct LOGGING_DATA_ACKED_DATA {
16454 #[doc = "sequence number (can wrap)"]
16455 pub sequence: u16,
16456 #[doc = "system ID of the target"]
16457 pub target_system: u8,
16458 #[doc = "component ID of the target"]
16459 pub target_component: u8,
16460 #[doc = "data length"]
16461 pub length: u8,
16462 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
16463 pub first_message_offset: u8,
16464 #[doc = "logged data"]
16465 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
16466 pub data: [u8; 249],
16467}
16468impl LOGGING_DATA_ACKED_DATA {
16469 pub const ENCODED_LEN: usize = 255usize;
16470 pub const DEFAULT: Self = Self {
16471 sequence: 0_u16,
16472 target_system: 0_u8,
16473 target_component: 0_u8,
16474 length: 0_u8,
16475 first_message_offset: 0_u8,
16476 data: [0_u8; 249usize],
16477 };
16478 #[cfg(feature = "arbitrary")]
16479 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16480 use arbitrary::{Arbitrary, Unstructured};
16481 let mut buf = [0u8; 1024];
16482 rng.fill_bytes(&mut buf);
16483 let mut unstructured = Unstructured::new(&buf);
16484 Self::arbitrary(&mut unstructured).unwrap_or_default()
16485 }
16486}
16487impl Default for LOGGING_DATA_ACKED_DATA {
16488 fn default() -> Self {
16489 Self::DEFAULT.clone()
16490 }
16491}
16492impl MessageData for LOGGING_DATA_ACKED_DATA {
16493 type Message = MavMessage;
16494 const ID: u32 = 267u32;
16495 const NAME: &'static str = "LOGGING_DATA_ACKED";
16496 const EXTRA_CRC: u8 = 35u8;
16497 const ENCODED_LEN: usize = 255usize;
16498 fn deser(
16499 _version: MavlinkVersion,
16500 __input: &[u8],
16501 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16502 let avail_len = __input.len();
16503 let mut payload_buf = [0; Self::ENCODED_LEN];
16504 let mut buf = if avail_len < Self::ENCODED_LEN {
16505 payload_buf[0..avail_len].copy_from_slice(__input);
16506 Bytes::new(&payload_buf)
16507 } else {
16508 Bytes::new(__input)
16509 };
16510 let mut __struct = Self::default();
16511 __struct.sequence = buf.get_u16_le();
16512 __struct.target_system = buf.get_u8();
16513 __struct.target_component = buf.get_u8();
16514 __struct.length = buf.get_u8();
16515 __struct.first_message_offset = buf.get_u8();
16516 for v in &mut __struct.data {
16517 let val = buf.get_u8();
16518 *v = val;
16519 }
16520 Ok(__struct)
16521 }
16522 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16523 let mut __tmp = BytesMut::new(bytes);
16524 #[allow(clippy::absurd_extreme_comparisons)]
16525 #[allow(unused_comparisons)]
16526 if __tmp.remaining() < Self::ENCODED_LEN {
16527 panic!(
16528 "buffer is too small (need {} bytes, but got {})",
16529 Self::ENCODED_LEN,
16530 __tmp.remaining(),
16531 )
16532 }
16533 __tmp.put_u16_le(self.sequence);
16534 __tmp.put_u8(self.target_system);
16535 __tmp.put_u8(self.target_component);
16536 __tmp.put_u8(self.length);
16537 __tmp.put_u8(self.first_message_offset);
16538 for val in &self.data {
16539 __tmp.put_u8(*val);
16540 }
16541 if matches!(version, MavlinkVersion::V2) {
16542 let len = __tmp.len();
16543 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16544 } else {
16545 __tmp.len()
16546 }
16547 }
16548}
16549#[doc = "id: 35"]
16550#[doc = "The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
16551#[derive(Debug, Clone, PartialEq)]
16552#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16553#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16554pub struct RC_CHANNELS_RAW_DATA {
16555 #[doc = "Timestamp (time since system boot)."]
16556 pub time_boot_ms: u32,
16557 #[doc = "RC channel 1 value."]
16558 pub chan1_raw: u16,
16559 #[doc = "RC channel 2 value."]
16560 pub chan2_raw: u16,
16561 #[doc = "RC channel 3 value."]
16562 pub chan3_raw: u16,
16563 #[doc = "RC channel 4 value."]
16564 pub chan4_raw: u16,
16565 #[doc = "RC channel 5 value."]
16566 pub chan5_raw: u16,
16567 #[doc = "RC channel 6 value."]
16568 pub chan6_raw: u16,
16569 #[doc = "RC channel 7 value."]
16570 pub chan7_raw: u16,
16571 #[doc = "RC channel 8 value."]
16572 pub chan8_raw: u16,
16573 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
16574 pub port: u8,
16575 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
16576 pub rssi: u8,
16577}
16578impl RC_CHANNELS_RAW_DATA {
16579 pub const ENCODED_LEN: usize = 22usize;
16580 pub const DEFAULT: Self = Self {
16581 time_boot_ms: 0_u32,
16582 chan1_raw: 0_u16,
16583 chan2_raw: 0_u16,
16584 chan3_raw: 0_u16,
16585 chan4_raw: 0_u16,
16586 chan5_raw: 0_u16,
16587 chan6_raw: 0_u16,
16588 chan7_raw: 0_u16,
16589 chan8_raw: 0_u16,
16590 port: 0_u8,
16591 rssi: 0_u8,
16592 };
16593 #[cfg(feature = "arbitrary")]
16594 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16595 use arbitrary::{Arbitrary, Unstructured};
16596 let mut buf = [0u8; 1024];
16597 rng.fill_bytes(&mut buf);
16598 let mut unstructured = Unstructured::new(&buf);
16599 Self::arbitrary(&mut unstructured).unwrap_or_default()
16600 }
16601}
16602impl Default for RC_CHANNELS_RAW_DATA {
16603 fn default() -> Self {
16604 Self::DEFAULT.clone()
16605 }
16606}
16607impl MessageData for RC_CHANNELS_RAW_DATA {
16608 type Message = MavMessage;
16609 const ID: u32 = 35u32;
16610 const NAME: &'static str = "RC_CHANNELS_RAW";
16611 const EXTRA_CRC: u8 = 244u8;
16612 const ENCODED_LEN: usize = 22usize;
16613 fn deser(
16614 _version: MavlinkVersion,
16615 __input: &[u8],
16616 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16617 let avail_len = __input.len();
16618 let mut payload_buf = [0; Self::ENCODED_LEN];
16619 let mut buf = if avail_len < Self::ENCODED_LEN {
16620 payload_buf[0..avail_len].copy_from_slice(__input);
16621 Bytes::new(&payload_buf)
16622 } else {
16623 Bytes::new(__input)
16624 };
16625 let mut __struct = Self::default();
16626 __struct.time_boot_ms = buf.get_u32_le();
16627 __struct.chan1_raw = buf.get_u16_le();
16628 __struct.chan2_raw = buf.get_u16_le();
16629 __struct.chan3_raw = buf.get_u16_le();
16630 __struct.chan4_raw = buf.get_u16_le();
16631 __struct.chan5_raw = buf.get_u16_le();
16632 __struct.chan6_raw = buf.get_u16_le();
16633 __struct.chan7_raw = buf.get_u16_le();
16634 __struct.chan8_raw = buf.get_u16_le();
16635 __struct.port = buf.get_u8();
16636 __struct.rssi = buf.get_u8();
16637 Ok(__struct)
16638 }
16639 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16640 let mut __tmp = BytesMut::new(bytes);
16641 #[allow(clippy::absurd_extreme_comparisons)]
16642 #[allow(unused_comparisons)]
16643 if __tmp.remaining() < Self::ENCODED_LEN {
16644 panic!(
16645 "buffer is too small (need {} bytes, but got {})",
16646 Self::ENCODED_LEN,
16647 __tmp.remaining(),
16648 )
16649 }
16650 __tmp.put_u32_le(self.time_boot_ms);
16651 __tmp.put_u16_le(self.chan1_raw);
16652 __tmp.put_u16_le(self.chan2_raw);
16653 __tmp.put_u16_le(self.chan3_raw);
16654 __tmp.put_u16_le(self.chan4_raw);
16655 __tmp.put_u16_le(self.chan5_raw);
16656 __tmp.put_u16_le(self.chan6_raw);
16657 __tmp.put_u16_le(self.chan7_raw);
16658 __tmp.put_u16_le(self.chan8_raw);
16659 __tmp.put_u8(self.port);
16660 __tmp.put_u8(self.rssi);
16661 if matches!(version, MavlinkVersion::V2) {
16662 let len = __tmp.len();
16663 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16664 } else {
16665 __tmp.len()
16666 }
16667 }
16668}
16669#[doc = "id: 8"]
16670#[doc = "Status generated in each node in the communication chain and injected into MAVLink stream."]
16671#[derive(Debug, Clone, PartialEq)]
16672#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16673#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16674pub struct LINK_NODE_STATUS_DATA {
16675 #[doc = "Timestamp (time since system boot)."]
16676 pub timestamp: u64,
16677 #[doc = "Transmit rate"]
16678 pub tx_rate: u32,
16679 #[doc = "Receive rate"]
16680 pub rx_rate: u32,
16681 #[doc = "Messages sent"]
16682 pub messages_sent: u32,
16683 #[doc = "Messages received (estimated from counting seq)"]
16684 pub messages_received: u32,
16685 #[doc = "Messages lost (estimated from counting seq)"]
16686 pub messages_lost: u32,
16687 #[doc = "Number of bytes that could not be parsed correctly."]
16688 pub rx_parse_err: u16,
16689 #[doc = "Transmit buffer overflows. This number wraps around as it reaches UINT16_MAX"]
16690 pub tx_overflows: u16,
16691 #[doc = "Receive buffer overflows. This number wraps around as it reaches UINT16_MAX"]
16692 pub rx_overflows: u16,
16693 #[doc = "Remaining free transmit buffer space"]
16694 pub tx_buf: u8,
16695 #[doc = "Remaining free receive buffer space"]
16696 pub rx_buf: u8,
16697}
16698impl LINK_NODE_STATUS_DATA {
16699 pub const ENCODED_LEN: usize = 36usize;
16700 pub const DEFAULT: Self = Self {
16701 timestamp: 0_u64,
16702 tx_rate: 0_u32,
16703 rx_rate: 0_u32,
16704 messages_sent: 0_u32,
16705 messages_received: 0_u32,
16706 messages_lost: 0_u32,
16707 rx_parse_err: 0_u16,
16708 tx_overflows: 0_u16,
16709 rx_overflows: 0_u16,
16710 tx_buf: 0_u8,
16711 rx_buf: 0_u8,
16712 };
16713 #[cfg(feature = "arbitrary")]
16714 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16715 use arbitrary::{Arbitrary, Unstructured};
16716 let mut buf = [0u8; 1024];
16717 rng.fill_bytes(&mut buf);
16718 let mut unstructured = Unstructured::new(&buf);
16719 Self::arbitrary(&mut unstructured).unwrap_or_default()
16720 }
16721}
16722impl Default for LINK_NODE_STATUS_DATA {
16723 fn default() -> Self {
16724 Self::DEFAULT.clone()
16725 }
16726}
16727impl MessageData for LINK_NODE_STATUS_DATA {
16728 type Message = MavMessage;
16729 const ID: u32 = 8u32;
16730 const NAME: &'static str = "LINK_NODE_STATUS";
16731 const EXTRA_CRC: u8 = 117u8;
16732 const ENCODED_LEN: usize = 36usize;
16733 fn deser(
16734 _version: MavlinkVersion,
16735 __input: &[u8],
16736 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16737 let avail_len = __input.len();
16738 let mut payload_buf = [0; Self::ENCODED_LEN];
16739 let mut buf = if avail_len < Self::ENCODED_LEN {
16740 payload_buf[0..avail_len].copy_from_slice(__input);
16741 Bytes::new(&payload_buf)
16742 } else {
16743 Bytes::new(__input)
16744 };
16745 let mut __struct = Self::default();
16746 __struct.timestamp = buf.get_u64_le();
16747 __struct.tx_rate = buf.get_u32_le();
16748 __struct.rx_rate = buf.get_u32_le();
16749 __struct.messages_sent = buf.get_u32_le();
16750 __struct.messages_received = buf.get_u32_le();
16751 __struct.messages_lost = buf.get_u32_le();
16752 __struct.rx_parse_err = buf.get_u16_le();
16753 __struct.tx_overflows = buf.get_u16_le();
16754 __struct.rx_overflows = buf.get_u16_le();
16755 __struct.tx_buf = buf.get_u8();
16756 __struct.rx_buf = buf.get_u8();
16757 Ok(__struct)
16758 }
16759 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16760 let mut __tmp = BytesMut::new(bytes);
16761 #[allow(clippy::absurd_extreme_comparisons)]
16762 #[allow(unused_comparisons)]
16763 if __tmp.remaining() < Self::ENCODED_LEN {
16764 panic!(
16765 "buffer is too small (need {} bytes, but got {})",
16766 Self::ENCODED_LEN,
16767 __tmp.remaining(),
16768 )
16769 }
16770 __tmp.put_u64_le(self.timestamp);
16771 __tmp.put_u32_le(self.tx_rate);
16772 __tmp.put_u32_le(self.rx_rate);
16773 __tmp.put_u32_le(self.messages_sent);
16774 __tmp.put_u32_le(self.messages_received);
16775 __tmp.put_u32_le(self.messages_lost);
16776 __tmp.put_u16_le(self.rx_parse_err);
16777 __tmp.put_u16_le(self.tx_overflows);
16778 __tmp.put_u16_le(self.rx_overflows);
16779 __tmp.put_u8(self.tx_buf);
16780 __tmp.put_u8(self.rx_buf);
16781 if matches!(version, MavlinkVersion::V2) {
16782 let len = __tmp.len();
16783 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16784 } else {
16785 __tmp.len()
16786 }
16787 }
16788}
16789#[doc = "id: 46"]
16790#[doc = "A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint."]
16791#[derive(Debug, Clone, PartialEq)]
16792#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16793#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16794pub struct MISSION_ITEM_REACHED_DATA {
16795 #[doc = "Sequence"]
16796 pub seq: u16,
16797}
16798impl MISSION_ITEM_REACHED_DATA {
16799 pub const ENCODED_LEN: usize = 2usize;
16800 pub const DEFAULT: Self = Self { seq: 0_u16 };
16801 #[cfg(feature = "arbitrary")]
16802 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16803 use arbitrary::{Arbitrary, Unstructured};
16804 let mut buf = [0u8; 1024];
16805 rng.fill_bytes(&mut buf);
16806 let mut unstructured = Unstructured::new(&buf);
16807 Self::arbitrary(&mut unstructured).unwrap_or_default()
16808 }
16809}
16810impl Default for MISSION_ITEM_REACHED_DATA {
16811 fn default() -> Self {
16812 Self::DEFAULT.clone()
16813 }
16814}
16815impl MessageData for MISSION_ITEM_REACHED_DATA {
16816 type Message = MavMessage;
16817 const ID: u32 = 46u32;
16818 const NAME: &'static str = "MISSION_ITEM_REACHED";
16819 const EXTRA_CRC: u8 = 11u8;
16820 const ENCODED_LEN: usize = 2usize;
16821 fn deser(
16822 _version: MavlinkVersion,
16823 __input: &[u8],
16824 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16825 let avail_len = __input.len();
16826 let mut payload_buf = [0; Self::ENCODED_LEN];
16827 let mut buf = if avail_len < Self::ENCODED_LEN {
16828 payload_buf[0..avail_len].copy_from_slice(__input);
16829 Bytes::new(&payload_buf)
16830 } else {
16831 Bytes::new(__input)
16832 };
16833 let mut __struct = Self::default();
16834 __struct.seq = buf.get_u16_le();
16835 Ok(__struct)
16836 }
16837 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16838 let mut __tmp = BytesMut::new(bytes);
16839 #[allow(clippy::absurd_extreme_comparisons)]
16840 #[allow(unused_comparisons)]
16841 if __tmp.remaining() < Self::ENCODED_LEN {
16842 panic!(
16843 "buffer is too small (need {} bytes, but got {})",
16844 Self::ENCODED_LEN,
16845 __tmp.remaining(),
16846 )
16847 }
16848 __tmp.put_u16_le(self.seq);
16849 if matches!(version, MavlinkVersion::V2) {
16850 let len = __tmp.len();
16851 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
16852 } else {
16853 __tmp.len()
16854 }
16855 }
16856}
16857#[doc = "id: 86"]
16858#[doc = "Sets a desired vehicle position, velocity, and/or acceleration in a global coordinate system (WGS84). Used by an external controller to command the vehicle (manual controller or other system)."]
16859#[derive(Debug, Clone, PartialEq)]
16860#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
16861#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
16862pub struct SET_POSITION_TARGET_GLOBAL_INT_DATA {
16863 #[doc = "Timestamp (time since system boot). The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency."]
16864 pub time_boot_ms: u32,
16865 #[doc = "Latitude in WGS84 frame"]
16866 pub lat_int: i32,
16867 #[doc = "Longitude in WGS84 frame"]
16868 pub lon_int: i32,
16869 #[doc = "Altitude (MSL, Relative to home, or AGL - depending on frame)"]
16870 pub alt: f32,
16871 #[doc = "X velocity in NED frame"]
16872 pub vx: f32,
16873 #[doc = "Y velocity in NED frame"]
16874 pub vy: f32,
16875 #[doc = "Z velocity in NED frame"]
16876 pub vz: f32,
16877 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
16878 pub afx: f32,
16879 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
16880 pub afy: f32,
16881 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
16882 pub afz: f32,
16883 #[doc = "yaw setpoint"]
16884 pub yaw: f32,
16885 #[doc = "yaw rate setpoint"]
16886 pub yaw_rate: f32,
16887 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
16888 pub type_mask: PositionTargetTypemask,
16889 #[doc = "System ID"]
16890 pub target_system: u8,
16891 #[doc = "Component ID"]
16892 pub target_component: u8,
16893 #[doc = "Valid options are: MAV_FRAME_GLOBAL = 0, MAV_FRAME_GLOBAL_RELATIVE_ALT = 3, MAV_FRAME_GLOBAL_TERRAIN_ALT = 10 (MAV_FRAME_GLOBAL_INT, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT are allowed synonyms, but have been deprecated)"]
16894 pub coordinate_frame: MavFrame,
16895}
16896impl SET_POSITION_TARGET_GLOBAL_INT_DATA {
16897 pub const ENCODED_LEN: usize = 53usize;
16898 pub const DEFAULT: Self = Self {
16899 time_boot_ms: 0_u32,
16900 lat_int: 0_i32,
16901 lon_int: 0_i32,
16902 alt: 0.0_f32,
16903 vx: 0.0_f32,
16904 vy: 0.0_f32,
16905 vz: 0.0_f32,
16906 afx: 0.0_f32,
16907 afy: 0.0_f32,
16908 afz: 0.0_f32,
16909 yaw: 0.0_f32,
16910 yaw_rate: 0.0_f32,
16911 type_mask: PositionTargetTypemask::DEFAULT,
16912 target_system: 0_u8,
16913 target_component: 0_u8,
16914 coordinate_frame: MavFrame::DEFAULT,
16915 };
16916 #[cfg(feature = "arbitrary")]
16917 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
16918 use arbitrary::{Arbitrary, Unstructured};
16919 let mut buf = [0u8; 1024];
16920 rng.fill_bytes(&mut buf);
16921 let mut unstructured = Unstructured::new(&buf);
16922 Self::arbitrary(&mut unstructured).unwrap_or_default()
16923 }
16924}
16925impl Default for SET_POSITION_TARGET_GLOBAL_INT_DATA {
16926 fn default() -> Self {
16927 Self::DEFAULT.clone()
16928 }
16929}
16930impl MessageData for SET_POSITION_TARGET_GLOBAL_INT_DATA {
16931 type Message = MavMessage;
16932 const ID: u32 = 86u32;
16933 const NAME: &'static str = "SET_POSITION_TARGET_GLOBAL_INT";
16934 const EXTRA_CRC: u8 = 5u8;
16935 const ENCODED_LEN: usize = 53usize;
16936 fn deser(
16937 _version: MavlinkVersion,
16938 __input: &[u8],
16939 ) -> Result<Self, ::mavlink_core::error::ParserError> {
16940 let avail_len = __input.len();
16941 let mut payload_buf = [0; Self::ENCODED_LEN];
16942 let mut buf = if avail_len < Self::ENCODED_LEN {
16943 payload_buf[0..avail_len].copy_from_slice(__input);
16944 Bytes::new(&payload_buf)
16945 } else {
16946 Bytes::new(__input)
16947 };
16948 let mut __struct = Self::default();
16949 __struct.time_boot_ms = buf.get_u32_le();
16950 __struct.lat_int = buf.get_i32_le();
16951 __struct.lon_int = buf.get_i32_le();
16952 __struct.alt = buf.get_f32_le();
16953 __struct.vx = buf.get_f32_le();
16954 __struct.vy = buf.get_f32_le();
16955 __struct.vz = buf.get_f32_le();
16956 __struct.afx = buf.get_f32_le();
16957 __struct.afy = buf.get_f32_le();
16958 __struct.afz = buf.get_f32_le();
16959 __struct.yaw = buf.get_f32_le();
16960 __struct.yaw_rate = buf.get_f32_le();
16961 let tmp = buf.get_u16_le();
16962 __struct.type_mask = PositionTargetTypemask::from_bits(
16963 tmp & PositionTargetTypemask::all().bits(),
16964 )
16965 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
16966 flag_type: "PositionTargetTypemask",
16967 value: tmp as u32,
16968 })?;
16969 __struct.target_system = buf.get_u8();
16970 __struct.target_component = buf.get_u8();
16971 let tmp = buf.get_u8();
16972 __struct.coordinate_frame =
16973 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
16974 enum_type: "MavFrame",
16975 value: tmp as u32,
16976 })?;
16977 Ok(__struct)
16978 }
16979 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
16980 let mut __tmp = BytesMut::new(bytes);
16981 #[allow(clippy::absurd_extreme_comparisons)]
16982 #[allow(unused_comparisons)]
16983 if __tmp.remaining() < Self::ENCODED_LEN {
16984 panic!(
16985 "buffer is too small (need {} bytes, but got {})",
16986 Self::ENCODED_LEN,
16987 __tmp.remaining(),
16988 )
16989 }
16990 __tmp.put_u32_le(self.time_boot_ms);
16991 __tmp.put_i32_le(self.lat_int);
16992 __tmp.put_i32_le(self.lon_int);
16993 __tmp.put_f32_le(self.alt);
16994 __tmp.put_f32_le(self.vx);
16995 __tmp.put_f32_le(self.vy);
16996 __tmp.put_f32_le(self.vz);
16997 __tmp.put_f32_le(self.afx);
16998 __tmp.put_f32_le(self.afy);
16999 __tmp.put_f32_le(self.afz);
17000 __tmp.put_f32_le(self.yaw);
17001 __tmp.put_f32_le(self.yaw_rate);
17002 __tmp.put_u16_le(self.type_mask.bits());
17003 __tmp.put_u8(self.target_system);
17004 __tmp.put_u8(self.target_component);
17005 __tmp.put_u8(self.coordinate_frame as u8);
17006 if matches!(version, MavlinkVersion::V2) {
17007 let len = __tmp.len();
17008 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17009 } else {
17010 __tmp.len()
17011 }
17012 }
17013}
17014#[doc = "id: 370"]
17015#[doc = "Smart Battery information (static/infrequent update). Use for updates from: smart battery to flight stack, flight stack to GCS. Use BATTERY_STATUS for the frequent battery updates."]
17016#[derive(Debug, Clone, PartialEq)]
17017#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17018#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17019pub struct SMART_BATTERY_INFO_DATA {
17020 #[doc = "Capacity when full according to manufacturer, -1: field not provided."]
17021 pub capacity_full_specification: i32,
17022 #[doc = "Capacity when full (accounting for battery degradation), -1: field not provided."]
17023 pub capacity_full: i32,
17024 #[doc = "Charge/discharge cycle count. UINT16_MAX: field not provided."]
17025 pub cycle_count: u16,
17026 #[doc = "Battery weight. 0: field not provided."]
17027 pub weight: u16,
17028 #[doc = "Minimum per-cell voltage when discharging. If not supplied set to UINT16_MAX value."]
17029 pub discharge_minimum_voltage: u16,
17030 #[doc = "Minimum per-cell voltage when charging. If not supplied set to UINT16_MAX value."]
17031 pub charging_minimum_voltage: u16,
17032 #[doc = "Minimum per-cell voltage when resting. If not supplied set to UINT16_MAX value."]
17033 pub resting_minimum_voltage: u16,
17034 #[doc = "Battery ID"]
17035 pub id: u8,
17036 #[doc = "Function of the battery"]
17037 pub battery_function: MavBatteryFunction,
17038 #[doc = "Type (chemistry) of the battery"]
17039 pub mavtype: MavBatteryType,
17040 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
17041 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17042 pub serial_number: [u8; 16],
17043 #[doc = "Static device name in ASCII characters, 0 terminated. All 0: field not provided. Encode as manufacturer name then product name separated using an underscore."]
17044 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17045 pub device_name: [u8; 50],
17046 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
17047 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17048 pub charging_maximum_voltage: u16,
17049 #[doc = "Number of battery cells in series. 0: field not provided."]
17050 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17051 pub cells_in_series: u8,
17052 #[doc = "Maximum pack discharge current. 0: field not provided."]
17053 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17054 pub discharge_maximum_current: u32,
17055 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
17056 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17057 pub discharge_maximum_burst_current: u32,
17058 #[doc = "Manufacture date (DD/MM/YYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
17059 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17060 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17061 pub manufacture_date: [u8; 11],
17062}
17063impl SMART_BATTERY_INFO_DATA {
17064 pub const ENCODED_LEN: usize = 109usize;
17065 pub const DEFAULT: Self = Self {
17066 capacity_full_specification: 0_i32,
17067 capacity_full: 0_i32,
17068 cycle_count: 0_u16,
17069 weight: 0_u16,
17070 discharge_minimum_voltage: 0_u16,
17071 charging_minimum_voltage: 0_u16,
17072 resting_minimum_voltage: 0_u16,
17073 id: 0_u8,
17074 battery_function: MavBatteryFunction::DEFAULT,
17075 mavtype: MavBatteryType::DEFAULT,
17076 serial_number: [0_u8; 16usize],
17077 device_name: [0_u8; 50usize],
17078 charging_maximum_voltage: 0_u16,
17079 cells_in_series: 0_u8,
17080 discharge_maximum_current: 0_u32,
17081 discharge_maximum_burst_current: 0_u32,
17082 manufacture_date: [0_u8; 11usize],
17083 };
17084 #[cfg(feature = "arbitrary")]
17085 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17086 use arbitrary::{Arbitrary, Unstructured};
17087 let mut buf = [0u8; 1024];
17088 rng.fill_bytes(&mut buf);
17089 let mut unstructured = Unstructured::new(&buf);
17090 Self::arbitrary(&mut unstructured).unwrap_or_default()
17091 }
17092}
17093impl Default for SMART_BATTERY_INFO_DATA {
17094 fn default() -> Self {
17095 Self::DEFAULT.clone()
17096 }
17097}
17098impl MessageData for SMART_BATTERY_INFO_DATA {
17099 type Message = MavMessage;
17100 const ID: u32 = 370u32;
17101 const NAME: &'static str = "SMART_BATTERY_INFO";
17102 const EXTRA_CRC: u8 = 75u8;
17103 const ENCODED_LEN: usize = 109usize;
17104 fn deser(
17105 _version: MavlinkVersion,
17106 __input: &[u8],
17107 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17108 let avail_len = __input.len();
17109 let mut payload_buf = [0; Self::ENCODED_LEN];
17110 let mut buf = if avail_len < Self::ENCODED_LEN {
17111 payload_buf[0..avail_len].copy_from_slice(__input);
17112 Bytes::new(&payload_buf)
17113 } else {
17114 Bytes::new(__input)
17115 };
17116 let mut __struct = Self::default();
17117 __struct.capacity_full_specification = buf.get_i32_le();
17118 __struct.capacity_full = buf.get_i32_le();
17119 __struct.cycle_count = buf.get_u16_le();
17120 __struct.weight = buf.get_u16_le();
17121 __struct.discharge_minimum_voltage = buf.get_u16_le();
17122 __struct.charging_minimum_voltage = buf.get_u16_le();
17123 __struct.resting_minimum_voltage = buf.get_u16_le();
17124 __struct.id = buf.get_u8();
17125 let tmp = buf.get_u8();
17126 __struct.battery_function =
17127 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17128 enum_type: "MavBatteryFunction",
17129 value: tmp as u32,
17130 })?;
17131 let tmp = buf.get_u8();
17132 __struct.mavtype =
17133 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17134 enum_type: "MavBatteryType",
17135 value: tmp as u32,
17136 })?;
17137 for v in &mut __struct.serial_number {
17138 let val = buf.get_u8();
17139 *v = val;
17140 }
17141 for v in &mut __struct.device_name {
17142 let val = buf.get_u8();
17143 *v = val;
17144 }
17145 __struct.charging_maximum_voltage = buf.get_u16_le();
17146 __struct.cells_in_series = buf.get_u8();
17147 __struct.discharge_maximum_current = buf.get_u32_le();
17148 __struct.discharge_maximum_burst_current = buf.get_u32_le();
17149 for v in &mut __struct.manufacture_date {
17150 let val = buf.get_u8();
17151 *v = val;
17152 }
17153 Ok(__struct)
17154 }
17155 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17156 let mut __tmp = BytesMut::new(bytes);
17157 #[allow(clippy::absurd_extreme_comparisons)]
17158 #[allow(unused_comparisons)]
17159 if __tmp.remaining() < Self::ENCODED_LEN {
17160 panic!(
17161 "buffer is too small (need {} bytes, but got {})",
17162 Self::ENCODED_LEN,
17163 __tmp.remaining(),
17164 )
17165 }
17166 __tmp.put_i32_le(self.capacity_full_specification);
17167 __tmp.put_i32_le(self.capacity_full);
17168 __tmp.put_u16_le(self.cycle_count);
17169 __tmp.put_u16_le(self.weight);
17170 __tmp.put_u16_le(self.discharge_minimum_voltage);
17171 __tmp.put_u16_le(self.charging_minimum_voltage);
17172 __tmp.put_u16_le(self.resting_minimum_voltage);
17173 __tmp.put_u8(self.id);
17174 __tmp.put_u8(self.battery_function as u8);
17175 __tmp.put_u8(self.mavtype as u8);
17176 for val in &self.serial_number {
17177 __tmp.put_u8(*val);
17178 }
17179 for val in &self.device_name {
17180 __tmp.put_u8(*val);
17181 }
17182 __tmp.put_u16_le(self.charging_maximum_voltage);
17183 __tmp.put_u8(self.cells_in_series);
17184 __tmp.put_u32_le(self.discharge_maximum_current);
17185 __tmp.put_u32_le(self.discharge_maximum_burst_current);
17186 for val in &self.manufacture_date {
17187 __tmp.put_u8(*val);
17188 }
17189 if matches!(version, MavlinkVersion::V2) {
17190 let len = __tmp.len();
17191 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17192 } else {
17193 __tmp.len()
17194 }
17195 }
17196}
17197#[doc = "id: 48"]
17198#[doc = "Sets the GPS coordinates of the vehicle local origin (0,0,0) position. Vehicle should emit GPS_GLOBAL_ORIGIN irrespective of whether the origin is changed. This enables transform between the local coordinate frame and the global (GPS) coordinate frame, which may be necessary when (for example) indoor and outdoor settings are connected and the MAV should move from in- to outdoor."]
17199#[derive(Debug, Clone, PartialEq)]
17200#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17201#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17202pub struct SET_GPS_GLOBAL_ORIGIN_DATA {
17203 #[doc = "Latitude (WGS84)"]
17204 pub latitude: i32,
17205 #[doc = "Longitude (WGS84)"]
17206 pub longitude: i32,
17207 #[doc = "Altitude (MSL). Positive for up."]
17208 pub altitude: i32,
17209 #[doc = "System ID"]
17210 pub target_system: u8,
17211 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17212 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
17213 pub time_usec: u64,
17214}
17215impl SET_GPS_GLOBAL_ORIGIN_DATA {
17216 pub const ENCODED_LEN: usize = 21usize;
17217 pub const DEFAULT: Self = Self {
17218 latitude: 0_i32,
17219 longitude: 0_i32,
17220 altitude: 0_i32,
17221 target_system: 0_u8,
17222 time_usec: 0_u64,
17223 };
17224 #[cfg(feature = "arbitrary")]
17225 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17226 use arbitrary::{Arbitrary, Unstructured};
17227 let mut buf = [0u8; 1024];
17228 rng.fill_bytes(&mut buf);
17229 let mut unstructured = Unstructured::new(&buf);
17230 Self::arbitrary(&mut unstructured).unwrap_or_default()
17231 }
17232}
17233impl Default for SET_GPS_GLOBAL_ORIGIN_DATA {
17234 fn default() -> Self {
17235 Self::DEFAULT.clone()
17236 }
17237}
17238impl MessageData for SET_GPS_GLOBAL_ORIGIN_DATA {
17239 type Message = MavMessage;
17240 const ID: u32 = 48u32;
17241 const NAME: &'static str = "SET_GPS_GLOBAL_ORIGIN";
17242 const EXTRA_CRC: u8 = 41u8;
17243 const ENCODED_LEN: usize = 21usize;
17244 fn deser(
17245 _version: MavlinkVersion,
17246 __input: &[u8],
17247 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17248 let avail_len = __input.len();
17249 let mut payload_buf = [0; Self::ENCODED_LEN];
17250 let mut buf = if avail_len < Self::ENCODED_LEN {
17251 payload_buf[0..avail_len].copy_from_slice(__input);
17252 Bytes::new(&payload_buf)
17253 } else {
17254 Bytes::new(__input)
17255 };
17256 let mut __struct = Self::default();
17257 __struct.latitude = buf.get_i32_le();
17258 __struct.longitude = buf.get_i32_le();
17259 __struct.altitude = buf.get_i32_le();
17260 __struct.target_system = buf.get_u8();
17261 __struct.time_usec = buf.get_u64_le();
17262 Ok(__struct)
17263 }
17264 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17265 let mut __tmp = BytesMut::new(bytes);
17266 #[allow(clippy::absurd_extreme_comparisons)]
17267 #[allow(unused_comparisons)]
17268 if __tmp.remaining() < Self::ENCODED_LEN {
17269 panic!(
17270 "buffer is too small (need {} bytes, but got {})",
17271 Self::ENCODED_LEN,
17272 __tmp.remaining(),
17273 )
17274 }
17275 __tmp.put_i32_le(self.latitude);
17276 __tmp.put_i32_le(self.longitude);
17277 __tmp.put_i32_le(self.altitude);
17278 __tmp.put_u8(self.target_system);
17279 __tmp.put_u64_le(self.time_usec);
17280 if matches!(version, MavlinkVersion::V2) {
17281 let len = __tmp.len();
17282 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17283 } else {
17284 __tmp.len()
17285 }
17286 }
17287}
17288#[doc = "id: 241"]
17289#[doc = "Vibration levels and accelerometer clipping."]
17290#[derive(Debug, Clone, PartialEq)]
17291#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17292#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17293pub struct VIBRATION_DATA {
17294 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
17295 pub time_usec: u64,
17296 #[doc = "Vibration levels on X-axis"]
17297 pub vibration_x: f32,
17298 #[doc = "Vibration levels on Y-axis"]
17299 pub vibration_y: f32,
17300 #[doc = "Vibration levels on Z-axis"]
17301 pub vibration_z: f32,
17302 #[doc = "first accelerometer clipping count"]
17303 pub clipping_0: u32,
17304 #[doc = "second accelerometer clipping count"]
17305 pub clipping_1: u32,
17306 #[doc = "third accelerometer clipping count"]
17307 pub clipping_2: u32,
17308}
17309impl VIBRATION_DATA {
17310 pub const ENCODED_LEN: usize = 32usize;
17311 pub const DEFAULT: Self = Self {
17312 time_usec: 0_u64,
17313 vibration_x: 0.0_f32,
17314 vibration_y: 0.0_f32,
17315 vibration_z: 0.0_f32,
17316 clipping_0: 0_u32,
17317 clipping_1: 0_u32,
17318 clipping_2: 0_u32,
17319 };
17320 #[cfg(feature = "arbitrary")]
17321 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17322 use arbitrary::{Arbitrary, Unstructured};
17323 let mut buf = [0u8; 1024];
17324 rng.fill_bytes(&mut buf);
17325 let mut unstructured = Unstructured::new(&buf);
17326 Self::arbitrary(&mut unstructured).unwrap_or_default()
17327 }
17328}
17329impl Default for VIBRATION_DATA {
17330 fn default() -> Self {
17331 Self::DEFAULT.clone()
17332 }
17333}
17334impl MessageData for VIBRATION_DATA {
17335 type Message = MavMessage;
17336 const ID: u32 = 241u32;
17337 const NAME: &'static str = "VIBRATION";
17338 const EXTRA_CRC: u8 = 90u8;
17339 const ENCODED_LEN: usize = 32usize;
17340 fn deser(
17341 _version: MavlinkVersion,
17342 __input: &[u8],
17343 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17344 let avail_len = __input.len();
17345 let mut payload_buf = [0; Self::ENCODED_LEN];
17346 let mut buf = if avail_len < Self::ENCODED_LEN {
17347 payload_buf[0..avail_len].copy_from_slice(__input);
17348 Bytes::new(&payload_buf)
17349 } else {
17350 Bytes::new(__input)
17351 };
17352 let mut __struct = Self::default();
17353 __struct.time_usec = buf.get_u64_le();
17354 __struct.vibration_x = buf.get_f32_le();
17355 __struct.vibration_y = buf.get_f32_le();
17356 __struct.vibration_z = buf.get_f32_le();
17357 __struct.clipping_0 = buf.get_u32_le();
17358 __struct.clipping_1 = buf.get_u32_le();
17359 __struct.clipping_2 = buf.get_u32_le();
17360 Ok(__struct)
17361 }
17362 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17363 let mut __tmp = BytesMut::new(bytes);
17364 #[allow(clippy::absurd_extreme_comparisons)]
17365 #[allow(unused_comparisons)]
17366 if __tmp.remaining() < Self::ENCODED_LEN {
17367 panic!(
17368 "buffer is too small (need {} bytes, but got {})",
17369 Self::ENCODED_LEN,
17370 __tmp.remaining(),
17371 )
17372 }
17373 __tmp.put_u64_le(self.time_usec);
17374 __tmp.put_f32_le(self.vibration_x);
17375 __tmp.put_f32_le(self.vibration_y);
17376 __tmp.put_f32_le(self.vibration_z);
17377 __tmp.put_u32_le(self.clipping_0);
17378 __tmp.put_u32_le(self.clipping_1);
17379 __tmp.put_u32_le(self.clipping_2);
17380 if matches!(version, MavlinkVersion::V2) {
17381 let len = __tmp.len();
17382 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17383 } else {
17384 __tmp.len()
17385 }
17386 }
17387}
17388#[doc = "id: 281"]
17389#[doc = "Current status about a high level gimbal manager. This message should be broadcast at a low regular rate (e.g. 5Hz)."]
17390#[derive(Debug, Clone, PartialEq)]
17391#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17392#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17393pub struct GIMBAL_MANAGER_STATUS_DATA {
17394 #[doc = "Timestamp (time since system boot)."]
17395 pub time_boot_ms: u32,
17396 #[doc = "High level gimbal manager flags currently applied."]
17397 pub flags: GimbalManagerFlags,
17398 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
17399 pub gimbal_device_id: u8,
17400 #[doc = "System ID of MAVLink component with primary control, 0 for none."]
17401 pub primary_control_sysid: u8,
17402 #[doc = "Component ID of MAVLink component with primary control, 0 for none."]
17403 pub primary_control_compid: u8,
17404 #[doc = "System ID of MAVLink component with secondary control, 0 for none."]
17405 pub secondary_control_sysid: u8,
17406 #[doc = "Component ID of MAVLink component with secondary control, 0 for none."]
17407 pub secondary_control_compid: u8,
17408}
17409impl GIMBAL_MANAGER_STATUS_DATA {
17410 pub const ENCODED_LEN: usize = 13usize;
17411 pub const DEFAULT: Self = Self {
17412 time_boot_ms: 0_u32,
17413 flags: GimbalManagerFlags::DEFAULT,
17414 gimbal_device_id: 0_u8,
17415 primary_control_sysid: 0_u8,
17416 primary_control_compid: 0_u8,
17417 secondary_control_sysid: 0_u8,
17418 secondary_control_compid: 0_u8,
17419 };
17420 #[cfg(feature = "arbitrary")]
17421 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17422 use arbitrary::{Arbitrary, Unstructured};
17423 let mut buf = [0u8; 1024];
17424 rng.fill_bytes(&mut buf);
17425 let mut unstructured = Unstructured::new(&buf);
17426 Self::arbitrary(&mut unstructured).unwrap_or_default()
17427 }
17428}
17429impl Default for GIMBAL_MANAGER_STATUS_DATA {
17430 fn default() -> Self {
17431 Self::DEFAULT.clone()
17432 }
17433}
17434impl MessageData for GIMBAL_MANAGER_STATUS_DATA {
17435 type Message = MavMessage;
17436 const ID: u32 = 281u32;
17437 const NAME: &'static str = "GIMBAL_MANAGER_STATUS";
17438 const EXTRA_CRC: u8 = 48u8;
17439 const ENCODED_LEN: usize = 13usize;
17440 fn deser(
17441 _version: MavlinkVersion,
17442 __input: &[u8],
17443 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17444 let avail_len = __input.len();
17445 let mut payload_buf = [0; Self::ENCODED_LEN];
17446 let mut buf = if avail_len < Self::ENCODED_LEN {
17447 payload_buf[0..avail_len].copy_from_slice(__input);
17448 Bytes::new(&payload_buf)
17449 } else {
17450 Bytes::new(__input)
17451 };
17452 let mut __struct = Self::default();
17453 __struct.time_boot_ms = buf.get_u32_le();
17454 let tmp = buf.get_u32_le();
17455 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
17456 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
17457 flag_type: "GimbalManagerFlags",
17458 value: tmp as u32,
17459 })?;
17460 __struct.gimbal_device_id = buf.get_u8();
17461 __struct.primary_control_sysid = buf.get_u8();
17462 __struct.primary_control_compid = buf.get_u8();
17463 __struct.secondary_control_sysid = buf.get_u8();
17464 __struct.secondary_control_compid = buf.get_u8();
17465 Ok(__struct)
17466 }
17467 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17468 let mut __tmp = BytesMut::new(bytes);
17469 #[allow(clippy::absurd_extreme_comparisons)]
17470 #[allow(unused_comparisons)]
17471 if __tmp.remaining() < Self::ENCODED_LEN {
17472 panic!(
17473 "buffer is too small (need {} bytes, but got {})",
17474 Self::ENCODED_LEN,
17475 __tmp.remaining(),
17476 )
17477 }
17478 __tmp.put_u32_le(self.time_boot_ms);
17479 __tmp.put_u32_le(self.flags.bits());
17480 __tmp.put_u8(self.gimbal_device_id);
17481 __tmp.put_u8(self.primary_control_sysid);
17482 __tmp.put_u8(self.primary_control_compid);
17483 __tmp.put_u8(self.secondary_control_sysid);
17484 __tmp.put_u8(self.secondary_control_compid);
17485 if matches!(version, MavlinkVersion::V2) {
17486 let len = __tmp.len();
17487 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17488 } else {
17489 __tmp.len()
17490 }
17491 }
17492}
17493#[doc = "id: 73"]
17494#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN or INT32_MAX may be used in float/integer params (respectively) to indicate optional/default values (e.g. to use the component's current latitude, yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
17495#[derive(Debug, Clone, PartialEq)]
17496#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17497#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17498pub struct MISSION_ITEM_INT_DATA {
17499 #[doc = "PARAM1, see MAV_CMD enum"]
17500 pub param1: f32,
17501 #[doc = "PARAM2, see MAV_CMD enum"]
17502 pub param2: f32,
17503 #[doc = "PARAM3, see MAV_CMD enum"]
17504 pub param3: f32,
17505 #[doc = "PARAM4, see MAV_CMD enum"]
17506 pub param4: f32,
17507 #[doc = "PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7"]
17508 pub x: i32,
17509 #[doc = "PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7"]
17510 pub y: i32,
17511 #[doc = "PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame."]
17512 pub z: f32,
17513 #[doc = "Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4)."]
17514 pub seq: u16,
17515 #[doc = "The scheduled action for the waypoint."]
17516 pub command: MavCmd,
17517 #[doc = "System ID"]
17518 pub target_system: u8,
17519 #[doc = "Component ID"]
17520 pub target_component: u8,
17521 #[doc = "The coordinate system of the waypoint."]
17522 pub frame: MavFrame,
17523 #[doc = "false:0, true:1"]
17524 pub current: u8,
17525 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
17526 pub autocontinue: u8,
17527 #[doc = "Mission type."]
17528 #[cfg_attr(feature = "serde", serde(default))]
17529 pub mission_type: MavMissionType,
17530}
17531impl MISSION_ITEM_INT_DATA {
17532 pub const ENCODED_LEN: usize = 38usize;
17533 pub const DEFAULT: Self = Self {
17534 param1: 0.0_f32,
17535 param2: 0.0_f32,
17536 param3: 0.0_f32,
17537 param4: 0.0_f32,
17538 x: 0_i32,
17539 y: 0_i32,
17540 z: 0.0_f32,
17541 seq: 0_u16,
17542 command: MavCmd::DEFAULT,
17543 target_system: 0_u8,
17544 target_component: 0_u8,
17545 frame: MavFrame::DEFAULT,
17546 current: 0_u8,
17547 autocontinue: 0_u8,
17548 mission_type: MavMissionType::DEFAULT,
17549 };
17550 #[cfg(feature = "arbitrary")]
17551 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17552 use arbitrary::{Arbitrary, Unstructured};
17553 let mut buf = [0u8; 1024];
17554 rng.fill_bytes(&mut buf);
17555 let mut unstructured = Unstructured::new(&buf);
17556 Self::arbitrary(&mut unstructured).unwrap_or_default()
17557 }
17558}
17559impl Default for MISSION_ITEM_INT_DATA {
17560 fn default() -> Self {
17561 Self::DEFAULT.clone()
17562 }
17563}
17564impl MessageData for MISSION_ITEM_INT_DATA {
17565 type Message = MavMessage;
17566 const ID: u32 = 73u32;
17567 const NAME: &'static str = "MISSION_ITEM_INT";
17568 const EXTRA_CRC: u8 = 38u8;
17569 const ENCODED_LEN: usize = 38usize;
17570 fn deser(
17571 _version: MavlinkVersion,
17572 __input: &[u8],
17573 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17574 let avail_len = __input.len();
17575 let mut payload_buf = [0; Self::ENCODED_LEN];
17576 let mut buf = if avail_len < Self::ENCODED_LEN {
17577 payload_buf[0..avail_len].copy_from_slice(__input);
17578 Bytes::new(&payload_buf)
17579 } else {
17580 Bytes::new(__input)
17581 };
17582 let mut __struct = Self::default();
17583 __struct.param1 = buf.get_f32_le();
17584 __struct.param2 = buf.get_f32_le();
17585 __struct.param3 = buf.get_f32_le();
17586 __struct.param4 = buf.get_f32_le();
17587 __struct.x = buf.get_i32_le();
17588 __struct.y = buf.get_i32_le();
17589 __struct.z = buf.get_f32_le();
17590 __struct.seq = buf.get_u16_le();
17591 let tmp = buf.get_u16_le();
17592 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
17593 ::mavlink_core::error::ParserError::InvalidEnum {
17594 enum_type: "MavCmd",
17595 value: tmp as u32,
17596 },
17597 )?;
17598 __struct.target_system = buf.get_u8();
17599 __struct.target_component = buf.get_u8();
17600 let tmp = buf.get_u8();
17601 __struct.frame =
17602 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17603 enum_type: "MavFrame",
17604 value: tmp as u32,
17605 })?;
17606 __struct.current = buf.get_u8();
17607 __struct.autocontinue = buf.get_u8();
17608 let tmp = buf.get_u8();
17609 __struct.mission_type =
17610 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
17611 enum_type: "MavMissionType",
17612 value: tmp as u32,
17613 })?;
17614 Ok(__struct)
17615 }
17616 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17617 let mut __tmp = BytesMut::new(bytes);
17618 #[allow(clippy::absurd_extreme_comparisons)]
17619 #[allow(unused_comparisons)]
17620 if __tmp.remaining() < Self::ENCODED_LEN {
17621 panic!(
17622 "buffer is too small (need {} bytes, but got {})",
17623 Self::ENCODED_LEN,
17624 __tmp.remaining(),
17625 )
17626 }
17627 __tmp.put_f32_le(self.param1);
17628 __tmp.put_f32_le(self.param2);
17629 __tmp.put_f32_le(self.param3);
17630 __tmp.put_f32_le(self.param4);
17631 __tmp.put_i32_le(self.x);
17632 __tmp.put_i32_le(self.y);
17633 __tmp.put_f32_le(self.z);
17634 __tmp.put_u16_le(self.seq);
17635 __tmp.put_u16_le(self.command as u16);
17636 __tmp.put_u8(self.target_system);
17637 __tmp.put_u8(self.target_component);
17638 __tmp.put_u8(self.frame as u8);
17639 __tmp.put_u8(self.current);
17640 __tmp.put_u8(self.autocontinue);
17641 __tmp.put_u8(self.mission_type as u8);
17642 if matches!(version, MavlinkVersion::V2) {
17643 let len = __tmp.len();
17644 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17645 } else {
17646 __tmp.len()
17647 }
17648 }
17649}
17650#[doc = "id: 125"]
17651#[doc = "Power supply status."]
17652#[derive(Debug, Clone, PartialEq)]
17653#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17654#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17655pub struct POWER_STATUS_DATA {
17656 #[doc = "5V rail voltage."]
17657 pub Vcc: u16,
17658 #[doc = "Servo rail voltage."]
17659 pub Vservo: u16,
17660 #[doc = "Bitmap of power supply status flags."]
17661 pub flags: MavPowerStatus,
17662}
17663impl POWER_STATUS_DATA {
17664 pub const ENCODED_LEN: usize = 6usize;
17665 pub const DEFAULT: Self = Self {
17666 Vcc: 0_u16,
17667 Vservo: 0_u16,
17668 flags: MavPowerStatus::DEFAULT,
17669 };
17670 #[cfg(feature = "arbitrary")]
17671 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17672 use arbitrary::{Arbitrary, Unstructured};
17673 let mut buf = [0u8; 1024];
17674 rng.fill_bytes(&mut buf);
17675 let mut unstructured = Unstructured::new(&buf);
17676 Self::arbitrary(&mut unstructured).unwrap_or_default()
17677 }
17678}
17679impl Default for POWER_STATUS_DATA {
17680 fn default() -> Self {
17681 Self::DEFAULT.clone()
17682 }
17683}
17684impl MessageData for POWER_STATUS_DATA {
17685 type Message = MavMessage;
17686 const ID: u32 = 125u32;
17687 const NAME: &'static str = "POWER_STATUS";
17688 const EXTRA_CRC: u8 = 203u8;
17689 const ENCODED_LEN: usize = 6usize;
17690 fn deser(
17691 _version: MavlinkVersion,
17692 __input: &[u8],
17693 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17694 let avail_len = __input.len();
17695 let mut payload_buf = [0; Self::ENCODED_LEN];
17696 let mut buf = if avail_len < Self::ENCODED_LEN {
17697 payload_buf[0..avail_len].copy_from_slice(__input);
17698 Bytes::new(&payload_buf)
17699 } else {
17700 Bytes::new(__input)
17701 };
17702 let mut __struct = Self::default();
17703 __struct.Vcc = buf.get_u16_le();
17704 __struct.Vservo = buf.get_u16_le();
17705 let tmp = buf.get_u16_le();
17706 __struct.flags = MavPowerStatus::from_bits(tmp & MavPowerStatus::all().bits()).ok_or(
17707 ::mavlink_core::error::ParserError::InvalidFlag {
17708 flag_type: "MavPowerStatus",
17709 value: tmp as u32,
17710 },
17711 )?;
17712 Ok(__struct)
17713 }
17714 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17715 let mut __tmp = BytesMut::new(bytes);
17716 #[allow(clippy::absurd_extreme_comparisons)]
17717 #[allow(unused_comparisons)]
17718 if __tmp.remaining() < Self::ENCODED_LEN {
17719 panic!(
17720 "buffer is too small (need {} bytes, but got {})",
17721 Self::ENCODED_LEN,
17722 __tmp.remaining(),
17723 )
17724 }
17725 __tmp.put_u16_le(self.Vcc);
17726 __tmp.put_u16_le(self.Vservo);
17727 __tmp.put_u16_le(self.flags.bits());
17728 if matches!(version, MavlinkVersion::V2) {
17729 let len = __tmp.len();
17730 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17731 } else {
17732 __tmp.len()
17733 }
17734 }
17735}
17736#[doc = "id: 266"]
17737#[doc = "A message containing logged data (see also MAV_CMD_LOGGING_START)."]
17738#[derive(Debug, Clone, PartialEq)]
17739#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17740#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17741pub struct LOGGING_DATA_DATA {
17742 #[doc = "sequence number (can wrap)"]
17743 pub sequence: u16,
17744 #[doc = "system ID of the target"]
17745 pub target_system: u8,
17746 #[doc = "component ID of the target"]
17747 pub target_component: u8,
17748 #[doc = "data length"]
17749 pub length: u8,
17750 #[doc = "offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to UINT8_MAX if no start exists)."]
17751 pub first_message_offset: u8,
17752 #[doc = "logged data"]
17753 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
17754 pub data: [u8; 249],
17755}
17756impl LOGGING_DATA_DATA {
17757 pub const ENCODED_LEN: usize = 255usize;
17758 pub const DEFAULT: Self = Self {
17759 sequence: 0_u16,
17760 target_system: 0_u8,
17761 target_component: 0_u8,
17762 length: 0_u8,
17763 first_message_offset: 0_u8,
17764 data: [0_u8; 249usize],
17765 };
17766 #[cfg(feature = "arbitrary")]
17767 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17768 use arbitrary::{Arbitrary, Unstructured};
17769 let mut buf = [0u8; 1024];
17770 rng.fill_bytes(&mut buf);
17771 let mut unstructured = Unstructured::new(&buf);
17772 Self::arbitrary(&mut unstructured).unwrap_or_default()
17773 }
17774}
17775impl Default for LOGGING_DATA_DATA {
17776 fn default() -> Self {
17777 Self::DEFAULT.clone()
17778 }
17779}
17780impl MessageData for LOGGING_DATA_DATA {
17781 type Message = MavMessage;
17782 const ID: u32 = 266u32;
17783 const NAME: &'static str = "LOGGING_DATA";
17784 const EXTRA_CRC: u8 = 193u8;
17785 const ENCODED_LEN: usize = 255usize;
17786 fn deser(
17787 _version: MavlinkVersion,
17788 __input: &[u8],
17789 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17790 let avail_len = __input.len();
17791 let mut payload_buf = [0; Self::ENCODED_LEN];
17792 let mut buf = if avail_len < Self::ENCODED_LEN {
17793 payload_buf[0..avail_len].copy_from_slice(__input);
17794 Bytes::new(&payload_buf)
17795 } else {
17796 Bytes::new(__input)
17797 };
17798 let mut __struct = Self::default();
17799 __struct.sequence = buf.get_u16_le();
17800 __struct.target_system = buf.get_u8();
17801 __struct.target_component = buf.get_u8();
17802 __struct.length = buf.get_u8();
17803 __struct.first_message_offset = buf.get_u8();
17804 for v in &mut __struct.data {
17805 let val = buf.get_u8();
17806 *v = val;
17807 }
17808 Ok(__struct)
17809 }
17810 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17811 let mut __tmp = BytesMut::new(bytes);
17812 #[allow(clippy::absurd_extreme_comparisons)]
17813 #[allow(unused_comparisons)]
17814 if __tmp.remaining() < Self::ENCODED_LEN {
17815 panic!(
17816 "buffer is too small (need {} bytes, but got {})",
17817 Self::ENCODED_LEN,
17818 __tmp.remaining(),
17819 )
17820 }
17821 __tmp.put_u16_le(self.sequence);
17822 __tmp.put_u8(self.target_system);
17823 __tmp.put_u8(self.target_component);
17824 __tmp.put_u8(self.length);
17825 __tmp.put_u8(self.first_message_offset);
17826 for val in &self.data {
17827 __tmp.put_u8(*val);
17828 }
17829 if matches!(version, MavlinkVersion::V2) {
17830 let len = __tmp.len();
17831 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17832 } else {
17833 __tmp.len()
17834 }
17835 }
17836}
17837#[doc = "id: 6"]
17838#[doc = "Accept / deny control of this MAV."]
17839#[derive(Debug, Clone, PartialEq)]
17840#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17841#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17842pub struct CHANGE_OPERATOR_CONTROL_ACK_DATA {
17843 #[doc = "ID of the GCS this message"]
17844 pub gcs_system_id: u8,
17845 #[doc = "0: request control of this MAV, 1: Release control of this MAV"]
17846 pub control_request: u8,
17847 #[doc = "0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control"]
17848 pub ack: u8,
17849}
17850impl CHANGE_OPERATOR_CONTROL_ACK_DATA {
17851 pub const ENCODED_LEN: usize = 3usize;
17852 pub const DEFAULT: Self = Self {
17853 gcs_system_id: 0_u8,
17854 control_request: 0_u8,
17855 ack: 0_u8,
17856 };
17857 #[cfg(feature = "arbitrary")]
17858 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17859 use arbitrary::{Arbitrary, Unstructured};
17860 let mut buf = [0u8; 1024];
17861 rng.fill_bytes(&mut buf);
17862 let mut unstructured = Unstructured::new(&buf);
17863 Self::arbitrary(&mut unstructured).unwrap_or_default()
17864 }
17865}
17866impl Default for CHANGE_OPERATOR_CONTROL_ACK_DATA {
17867 fn default() -> Self {
17868 Self::DEFAULT.clone()
17869 }
17870}
17871impl MessageData for CHANGE_OPERATOR_CONTROL_ACK_DATA {
17872 type Message = MavMessage;
17873 const ID: u32 = 6u32;
17874 const NAME: &'static str = "CHANGE_OPERATOR_CONTROL_ACK";
17875 const EXTRA_CRC: u8 = 104u8;
17876 const ENCODED_LEN: usize = 3usize;
17877 fn deser(
17878 _version: MavlinkVersion,
17879 __input: &[u8],
17880 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17881 let avail_len = __input.len();
17882 let mut payload_buf = [0; Self::ENCODED_LEN];
17883 let mut buf = if avail_len < Self::ENCODED_LEN {
17884 payload_buf[0..avail_len].copy_from_slice(__input);
17885 Bytes::new(&payload_buf)
17886 } else {
17887 Bytes::new(__input)
17888 };
17889 let mut __struct = Self::default();
17890 __struct.gcs_system_id = buf.get_u8();
17891 __struct.control_request = buf.get_u8();
17892 __struct.ack = buf.get_u8();
17893 Ok(__struct)
17894 }
17895 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
17896 let mut __tmp = BytesMut::new(bytes);
17897 #[allow(clippy::absurd_extreme_comparisons)]
17898 #[allow(unused_comparisons)]
17899 if __tmp.remaining() < Self::ENCODED_LEN {
17900 panic!(
17901 "buffer is too small (need {} bytes, but got {})",
17902 Self::ENCODED_LEN,
17903 __tmp.remaining(),
17904 )
17905 }
17906 __tmp.put_u8(self.gcs_system_id);
17907 __tmp.put_u8(self.control_request);
17908 __tmp.put_u8(self.ack);
17909 if matches!(version, MavlinkVersion::V2) {
17910 let len = __tmp.len();
17911 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
17912 } else {
17913 __tmp.len()
17914 }
17915 }
17916}
17917#[doc = "id: 127"]
17918#[doc = "RTK GPS data. Gives information on the relative baseline calculation the GPS is reporting."]
17919#[derive(Debug, Clone, PartialEq)]
17920#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
17921#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
17922pub struct GPS_RTK_DATA {
17923 #[doc = "Time since boot of last baseline message received."]
17924 pub time_last_baseline_ms: u32,
17925 #[doc = "GPS Time of Week of last baseline"]
17926 pub tow: u32,
17927 #[doc = "Current baseline in ECEF x or NED north component."]
17928 pub baseline_a_mm: i32,
17929 #[doc = "Current baseline in ECEF y or NED east component."]
17930 pub baseline_b_mm: i32,
17931 #[doc = "Current baseline in ECEF z or NED down component."]
17932 pub baseline_c_mm: i32,
17933 #[doc = "Current estimate of baseline accuracy."]
17934 pub accuracy: u32,
17935 #[doc = "Current number of integer ambiguity hypotheses."]
17936 pub iar_num_hypotheses: i32,
17937 #[doc = "GPS Week Number of last baseline"]
17938 pub wn: u16,
17939 #[doc = "Identification of connected RTK receiver."]
17940 pub rtk_receiver_id: u8,
17941 #[doc = "GPS-specific health report for RTK data."]
17942 pub rtk_health: u8,
17943 #[doc = "Rate of baseline messages being received by GPS"]
17944 pub rtk_rate: u8,
17945 #[doc = "Current number of sats used for RTK calculation."]
17946 pub nsats: u8,
17947 #[doc = "Coordinate system of baseline"]
17948 pub baseline_coords_type: RtkBaselineCoordinateSystem,
17949}
17950impl GPS_RTK_DATA {
17951 pub const ENCODED_LEN: usize = 35usize;
17952 pub const DEFAULT: Self = Self {
17953 time_last_baseline_ms: 0_u32,
17954 tow: 0_u32,
17955 baseline_a_mm: 0_i32,
17956 baseline_b_mm: 0_i32,
17957 baseline_c_mm: 0_i32,
17958 accuracy: 0_u32,
17959 iar_num_hypotheses: 0_i32,
17960 wn: 0_u16,
17961 rtk_receiver_id: 0_u8,
17962 rtk_health: 0_u8,
17963 rtk_rate: 0_u8,
17964 nsats: 0_u8,
17965 baseline_coords_type: RtkBaselineCoordinateSystem::DEFAULT,
17966 };
17967 #[cfg(feature = "arbitrary")]
17968 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
17969 use arbitrary::{Arbitrary, Unstructured};
17970 let mut buf = [0u8; 1024];
17971 rng.fill_bytes(&mut buf);
17972 let mut unstructured = Unstructured::new(&buf);
17973 Self::arbitrary(&mut unstructured).unwrap_or_default()
17974 }
17975}
17976impl Default for GPS_RTK_DATA {
17977 fn default() -> Self {
17978 Self::DEFAULT.clone()
17979 }
17980}
17981impl MessageData for GPS_RTK_DATA {
17982 type Message = MavMessage;
17983 const ID: u32 = 127u32;
17984 const NAME: &'static str = "GPS_RTK";
17985 const EXTRA_CRC: u8 = 25u8;
17986 const ENCODED_LEN: usize = 35usize;
17987 fn deser(
17988 _version: MavlinkVersion,
17989 __input: &[u8],
17990 ) -> Result<Self, ::mavlink_core::error::ParserError> {
17991 let avail_len = __input.len();
17992 let mut payload_buf = [0; Self::ENCODED_LEN];
17993 let mut buf = if avail_len < Self::ENCODED_LEN {
17994 payload_buf[0..avail_len].copy_from_slice(__input);
17995 Bytes::new(&payload_buf)
17996 } else {
17997 Bytes::new(__input)
17998 };
17999 let mut __struct = Self::default();
18000 __struct.time_last_baseline_ms = buf.get_u32_le();
18001 __struct.tow = buf.get_u32_le();
18002 __struct.baseline_a_mm = buf.get_i32_le();
18003 __struct.baseline_b_mm = buf.get_i32_le();
18004 __struct.baseline_c_mm = buf.get_i32_le();
18005 __struct.accuracy = buf.get_u32_le();
18006 __struct.iar_num_hypotheses = buf.get_i32_le();
18007 __struct.wn = buf.get_u16_le();
18008 __struct.rtk_receiver_id = buf.get_u8();
18009 __struct.rtk_health = buf.get_u8();
18010 __struct.rtk_rate = buf.get_u8();
18011 __struct.nsats = buf.get_u8();
18012 let tmp = buf.get_u8();
18013 __struct.baseline_coords_type =
18014 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18015 enum_type: "RtkBaselineCoordinateSystem",
18016 value: tmp as u32,
18017 })?;
18018 Ok(__struct)
18019 }
18020 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18021 let mut __tmp = BytesMut::new(bytes);
18022 #[allow(clippy::absurd_extreme_comparisons)]
18023 #[allow(unused_comparisons)]
18024 if __tmp.remaining() < Self::ENCODED_LEN {
18025 panic!(
18026 "buffer is too small (need {} bytes, but got {})",
18027 Self::ENCODED_LEN,
18028 __tmp.remaining(),
18029 )
18030 }
18031 __tmp.put_u32_le(self.time_last_baseline_ms);
18032 __tmp.put_u32_le(self.tow);
18033 __tmp.put_i32_le(self.baseline_a_mm);
18034 __tmp.put_i32_le(self.baseline_b_mm);
18035 __tmp.put_i32_le(self.baseline_c_mm);
18036 __tmp.put_u32_le(self.accuracy);
18037 __tmp.put_i32_le(self.iar_num_hypotheses);
18038 __tmp.put_u16_le(self.wn);
18039 __tmp.put_u8(self.rtk_receiver_id);
18040 __tmp.put_u8(self.rtk_health);
18041 __tmp.put_u8(self.rtk_rate);
18042 __tmp.put_u8(self.nsats);
18043 __tmp.put_u8(self.baseline_coords_type as u8);
18044 if matches!(version, MavlinkVersion::V2) {
18045 let len = __tmp.len();
18046 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18047 } else {
18048 __tmp.len()
18049 }
18050 }
18051}
18052#[doc = "id: 264"]
18053#[doc = "Flight information. This includes time since boot for arm, takeoff, and land, and a flight number. Takeoff and landing values reset to zero on arm. This can be requested using MAV_CMD_REQUEST_MESSAGE. Note, some fields are misnamed - timestamps are from boot (not UTC) and the flight_uuid is a sequence number."]
18054#[derive(Debug, Clone, PartialEq)]
18055#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18056#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18057pub struct FLIGHT_INFORMATION_DATA {
18058 #[doc = "Timestamp at arming (since system boot). Set to 0 on boot. Set value on arming. Note, field is misnamed UTC."]
18059 pub arming_time_utc: u64,
18060 #[doc = "Timestamp at takeoff (since system boot). Set to 0 at boot and on arming. Note, field is misnamed UTC."]
18061 pub takeoff_time_utc: u64,
18062 #[doc = "Flight number. Note, field is misnamed UUID."]
18063 pub flight_uuid: u64,
18064 #[doc = "Timestamp (time since system boot)."]
18065 pub time_boot_ms: u32,
18066 #[doc = "Timestamp at landing (in ms since system boot). Set to 0 at boot and on arming."]
18067 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18068 pub landing_time: u32,
18069}
18070impl FLIGHT_INFORMATION_DATA {
18071 pub const ENCODED_LEN: usize = 32usize;
18072 pub const DEFAULT: Self = Self {
18073 arming_time_utc: 0_u64,
18074 takeoff_time_utc: 0_u64,
18075 flight_uuid: 0_u64,
18076 time_boot_ms: 0_u32,
18077 landing_time: 0_u32,
18078 };
18079 #[cfg(feature = "arbitrary")]
18080 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18081 use arbitrary::{Arbitrary, Unstructured};
18082 let mut buf = [0u8; 1024];
18083 rng.fill_bytes(&mut buf);
18084 let mut unstructured = Unstructured::new(&buf);
18085 Self::arbitrary(&mut unstructured).unwrap_or_default()
18086 }
18087}
18088impl Default for FLIGHT_INFORMATION_DATA {
18089 fn default() -> Self {
18090 Self::DEFAULT.clone()
18091 }
18092}
18093impl MessageData for FLIGHT_INFORMATION_DATA {
18094 type Message = MavMessage;
18095 const ID: u32 = 264u32;
18096 const NAME: &'static str = "FLIGHT_INFORMATION";
18097 const EXTRA_CRC: u8 = 49u8;
18098 const ENCODED_LEN: usize = 32usize;
18099 fn deser(
18100 _version: MavlinkVersion,
18101 __input: &[u8],
18102 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18103 let avail_len = __input.len();
18104 let mut payload_buf = [0; Self::ENCODED_LEN];
18105 let mut buf = if avail_len < Self::ENCODED_LEN {
18106 payload_buf[0..avail_len].copy_from_slice(__input);
18107 Bytes::new(&payload_buf)
18108 } else {
18109 Bytes::new(__input)
18110 };
18111 let mut __struct = Self::default();
18112 __struct.arming_time_utc = buf.get_u64_le();
18113 __struct.takeoff_time_utc = buf.get_u64_le();
18114 __struct.flight_uuid = buf.get_u64_le();
18115 __struct.time_boot_ms = buf.get_u32_le();
18116 __struct.landing_time = buf.get_u32_le();
18117 Ok(__struct)
18118 }
18119 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18120 let mut __tmp = BytesMut::new(bytes);
18121 #[allow(clippy::absurd_extreme_comparisons)]
18122 #[allow(unused_comparisons)]
18123 if __tmp.remaining() < Self::ENCODED_LEN {
18124 panic!(
18125 "buffer is too small (need {} bytes, but got {})",
18126 Self::ENCODED_LEN,
18127 __tmp.remaining(),
18128 )
18129 }
18130 __tmp.put_u64_le(self.arming_time_utc);
18131 __tmp.put_u64_le(self.takeoff_time_utc);
18132 __tmp.put_u64_le(self.flight_uuid);
18133 __tmp.put_u32_le(self.time_boot_ms);
18134 __tmp.put_u32_le(self.landing_time);
18135 if matches!(version, MavlinkVersion::V2) {
18136 let len = __tmp.len();
18137 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18138 } else {
18139 __tmp.len()
18140 }
18141 }
18142}
18143#[doc = "id: 401"]
18144#[doc = "Tune formats supported by vehicle. This should be emitted as response to MAV_CMD_REQUEST_MESSAGE."]
18145#[derive(Debug, Clone, PartialEq)]
18146#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18147#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18148pub struct SUPPORTED_TUNES_DATA {
18149 #[doc = "Bitfield of supported tune formats."]
18150 pub format: TuneFormat,
18151 #[doc = "System ID"]
18152 pub target_system: u8,
18153 #[doc = "Component ID"]
18154 pub target_component: u8,
18155}
18156impl SUPPORTED_TUNES_DATA {
18157 pub const ENCODED_LEN: usize = 6usize;
18158 pub const DEFAULT: Self = Self {
18159 format: TuneFormat::DEFAULT,
18160 target_system: 0_u8,
18161 target_component: 0_u8,
18162 };
18163 #[cfg(feature = "arbitrary")]
18164 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18165 use arbitrary::{Arbitrary, Unstructured};
18166 let mut buf = [0u8; 1024];
18167 rng.fill_bytes(&mut buf);
18168 let mut unstructured = Unstructured::new(&buf);
18169 Self::arbitrary(&mut unstructured).unwrap_or_default()
18170 }
18171}
18172impl Default for SUPPORTED_TUNES_DATA {
18173 fn default() -> Self {
18174 Self::DEFAULT.clone()
18175 }
18176}
18177impl MessageData for SUPPORTED_TUNES_DATA {
18178 type Message = MavMessage;
18179 const ID: u32 = 401u32;
18180 const NAME: &'static str = "SUPPORTED_TUNES";
18181 const EXTRA_CRC: u8 = 183u8;
18182 const ENCODED_LEN: usize = 6usize;
18183 fn deser(
18184 _version: MavlinkVersion,
18185 __input: &[u8],
18186 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18187 let avail_len = __input.len();
18188 let mut payload_buf = [0; Self::ENCODED_LEN];
18189 let mut buf = if avail_len < Self::ENCODED_LEN {
18190 payload_buf[0..avail_len].copy_from_slice(__input);
18191 Bytes::new(&payload_buf)
18192 } else {
18193 Bytes::new(__input)
18194 };
18195 let mut __struct = Self::default();
18196 let tmp = buf.get_u32_le();
18197 __struct.format = FromPrimitive::from_u32(tmp).ok_or(
18198 ::mavlink_core::error::ParserError::InvalidEnum {
18199 enum_type: "TuneFormat",
18200 value: tmp as u32,
18201 },
18202 )?;
18203 __struct.target_system = buf.get_u8();
18204 __struct.target_component = buf.get_u8();
18205 Ok(__struct)
18206 }
18207 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18208 let mut __tmp = BytesMut::new(bytes);
18209 #[allow(clippy::absurd_extreme_comparisons)]
18210 #[allow(unused_comparisons)]
18211 if __tmp.remaining() < Self::ENCODED_LEN {
18212 panic!(
18213 "buffer is too small (need {} bytes, but got {})",
18214 Self::ENCODED_LEN,
18215 __tmp.remaining(),
18216 )
18217 }
18218 __tmp.put_u32_le(self.format as u32);
18219 __tmp.put_u8(self.target_system);
18220 __tmp.put_u8(self.target_component);
18221 if matches!(version, MavlinkVersion::V2) {
18222 let len = __tmp.len();
18223 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18224 } else {
18225 __tmp.len()
18226 }
18227 }
18228}
18229#[doc = "id: 299"]
18230#[doc = "Configure WiFi AP SSID, password, and mode. This message is re-emitted as an acknowledgement by the AP. The message may also be explicitly requested using MAV_CMD_REQUEST_MESSAGE."]
18231#[derive(Debug, Clone, PartialEq)]
18232#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18233#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18234pub struct WIFI_CONFIG_AP_DATA {
18235 #[doc = "Name of Wi-Fi network (SSID). Blank to leave it unchanged when setting. Current SSID when sent back as a response."]
18236 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18237 pub ssid: [u8; 32],
18238 #[doc = "Password. Blank for an open AP. MD5 hash when message is sent back as a response."]
18239 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18240 pub password: [u8; 64],
18241 #[doc = "WiFi Mode."]
18242 #[cfg_attr(feature = "serde", serde(default))]
18243 pub mode: WifiConfigApMode,
18244 #[doc = "Message acceptance response (sent back to GS)."]
18245 #[cfg_attr(feature = "serde", serde(default))]
18246 pub response: WifiConfigApResponse,
18247}
18248impl WIFI_CONFIG_AP_DATA {
18249 pub const ENCODED_LEN: usize = 98usize;
18250 pub const DEFAULT: Self = Self {
18251 ssid: [0_u8; 32usize],
18252 password: [0_u8; 64usize],
18253 mode: WifiConfigApMode::DEFAULT,
18254 response: WifiConfigApResponse::DEFAULT,
18255 };
18256 #[cfg(feature = "arbitrary")]
18257 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18258 use arbitrary::{Arbitrary, Unstructured};
18259 let mut buf = [0u8; 1024];
18260 rng.fill_bytes(&mut buf);
18261 let mut unstructured = Unstructured::new(&buf);
18262 Self::arbitrary(&mut unstructured).unwrap_or_default()
18263 }
18264}
18265impl Default for WIFI_CONFIG_AP_DATA {
18266 fn default() -> Self {
18267 Self::DEFAULT.clone()
18268 }
18269}
18270impl MessageData for WIFI_CONFIG_AP_DATA {
18271 type Message = MavMessage;
18272 const ID: u32 = 299u32;
18273 const NAME: &'static str = "WIFI_CONFIG_AP";
18274 const EXTRA_CRC: u8 = 19u8;
18275 const ENCODED_LEN: usize = 98usize;
18276 fn deser(
18277 _version: MavlinkVersion,
18278 __input: &[u8],
18279 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18280 let avail_len = __input.len();
18281 let mut payload_buf = [0; Self::ENCODED_LEN];
18282 let mut buf = if avail_len < Self::ENCODED_LEN {
18283 payload_buf[0..avail_len].copy_from_slice(__input);
18284 Bytes::new(&payload_buf)
18285 } else {
18286 Bytes::new(__input)
18287 };
18288 let mut __struct = Self::default();
18289 for v in &mut __struct.ssid {
18290 let val = buf.get_u8();
18291 *v = val;
18292 }
18293 for v in &mut __struct.password {
18294 let val = buf.get_u8();
18295 *v = val;
18296 }
18297 let tmp = buf.get_i8();
18298 __struct.mode =
18299 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18300 enum_type: "WifiConfigApMode",
18301 value: tmp as u32,
18302 })?;
18303 let tmp = buf.get_i8();
18304 __struct.response =
18305 FromPrimitive::from_i8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18306 enum_type: "WifiConfigApResponse",
18307 value: tmp as u32,
18308 })?;
18309 Ok(__struct)
18310 }
18311 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18312 let mut __tmp = BytesMut::new(bytes);
18313 #[allow(clippy::absurd_extreme_comparisons)]
18314 #[allow(unused_comparisons)]
18315 if __tmp.remaining() < Self::ENCODED_LEN {
18316 panic!(
18317 "buffer is too small (need {} bytes, but got {})",
18318 Self::ENCODED_LEN,
18319 __tmp.remaining(),
18320 )
18321 }
18322 for val in &self.ssid {
18323 __tmp.put_u8(*val);
18324 }
18325 for val in &self.password {
18326 __tmp.put_u8(*val);
18327 }
18328 __tmp.put_i8(self.mode as i8);
18329 __tmp.put_i8(self.response as i8);
18330 if matches!(version, MavlinkVersion::V2) {
18331 let len = __tmp.len();
18332 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18333 } else {
18334 __tmp.len()
18335 }
18336 }
18337}
18338#[doc = "id: 135"]
18339#[doc = "Request that the vehicle report terrain height at the given location (expected response is a TERRAIN_REPORT). Used by GCS to check if vehicle has all terrain data needed for a mission."]
18340#[derive(Debug, Clone, PartialEq)]
18341#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18342#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18343pub struct TERRAIN_CHECK_DATA {
18344 #[doc = "Latitude"]
18345 pub lat: i32,
18346 #[doc = "Longitude"]
18347 pub lon: i32,
18348}
18349impl TERRAIN_CHECK_DATA {
18350 pub const ENCODED_LEN: usize = 8usize;
18351 pub const DEFAULT: Self = Self {
18352 lat: 0_i32,
18353 lon: 0_i32,
18354 };
18355 #[cfg(feature = "arbitrary")]
18356 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18357 use arbitrary::{Arbitrary, Unstructured};
18358 let mut buf = [0u8; 1024];
18359 rng.fill_bytes(&mut buf);
18360 let mut unstructured = Unstructured::new(&buf);
18361 Self::arbitrary(&mut unstructured).unwrap_or_default()
18362 }
18363}
18364impl Default for TERRAIN_CHECK_DATA {
18365 fn default() -> Self {
18366 Self::DEFAULT.clone()
18367 }
18368}
18369impl MessageData for TERRAIN_CHECK_DATA {
18370 type Message = MavMessage;
18371 const ID: u32 = 135u32;
18372 const NAME: &'static str = "TERRAIN_CHECK";
18373 const EXTRA_CRC: u8 = 203u8;
18374 const ENCODED_LEN: usize = 8usize;
18375 fn deser(
18376 _version: MavlinkVersion,
18377 __input: &[u8],
18378 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18379 let avail_len = __input.len();
18380 let mut payload_buf = [0; Self::ENCODED_LEN];
18381 let mut buf = if avail_len < Self::ENCODED_LEN {
18382 payload_buf[0..avail_len].copy_from_slice(__input);
18383 Bytes::new(&payload_buf)
18384 } else {
18385 Bytes::new(__input)
18386 };
18387 let mut __struct = Self::default();
18388 __struct.lat = buf.get_i32_le();
18389 __struct.lon = buf.get_i32_le();
18390 Ok(__struct)
18391 }
18392 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18393 let mut __tmp = BytesMut::new(bytes);
18394 #[allow(clippy::absurd_extreme_comparisons)]
18395 #[allow(unused_comparisons)]
18396 if __tmp.remaining() < Self::ENCODED_LEN {
18397 panic!(
18398 "buffer is too small (need {} bytes, but got {})",
18399 Self::ENCODED_LEN,
18400 __tmp.remaining(),
18401 )
18402 }
18403 __tmp.put_i32_le(self.lat);
18404 __tmp.put_i32_le(self.lon);
18405 if matches!(version, MavlinkVersion::V2) {
18406 let len = __tmp.len();
18407 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18408 } else {
18409 __tmp.len()
18410 }
18411 }
18412}
18413#[doc = "id: 28"]
18414#[doc = "The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values."]
18415#[derive(Debug, Clone, PartialEq)]
18416#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18417#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18418pub struct RAW_PRESSURE_DATA {
18419 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18420 pub time_usec: u64,
18421 #[doc = "Absolute pressure (raw)"]
18422 pub press_abs: i16,
18423 #[doc = "Differential pressure 1 (raw, 0 if nonexistent)"]
18424 pub press_diff1: i16,
18425 #[doc = "Differential pressure 2 (raw, 0 if nonexistent)"]
18426 pub press_diff2: i16,
18427 #[doc = "Raw Temperature measurement (raw)"]
18428 pub temperature: i16,
18429}
18430impl RAW_PRESSURE_DATA {
18431 pub const ENCODED_LEN: usize = 16usize;
18432 pub const DEFAULT: Self = Self {
18433 time_usec: 0_u64,
18434 press_abs: 0_i16,
18435 press_diff1: 0_i16,
18436 press_diff2: 0_i16,
18437 temperature: 0_i16,
18438 };
18439 #[cfg(feature = "arbitrary")]
18440 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18441 use arbitrary::{Arbitrary, Unstructured};
18442 let mut buf = [0u8; 1024];
18443 rng.fill_bytes(&mut buf);
18444 let mut unstructured = Unstructured::new(&buf);
18445 Self::arbitrary(&mut unstructured).unwrap_or_default()
18446 }
18447}
18448impl Default for RAW_PRESSURE_DATA {
18449 fn default() -> Self {
18450 Self::DEFAULT.clone()
18451 }
18452}
18453impl MessageData for RAW_PRESSURE_DATA {
18454 type Message = MavMessage;
18455 const ID: u32 = 28u32;
18456 const NAME: &'static str = "RAW_PRESSURE";
18457 const EXTRA_CRC: u8 = 67u8;
18458 const ENCODED_LEN: usize = 16usize;
18459 fn deser(
18460 _version: MavlinkVersion,
18461 __input: &[u8],
18462 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18463 let avail_len = __input.len();
18464 let mut payload_buf = [0; Self::ENCODED_LEN];
18465 let mut buf = if avail_len < Self::ENCODED_LEN {
18466 payload_buf[0..avail_len].copy_from_slice(__input);
18467 Bytes::new(&payload_buf)
18468 } else {
18469 Bytes::new(__input)
18470 };
18471 let mut __struct = Self::default();
18472 __struct.time_usec = buf.get_u64_le();
18473 __struct.press_abs = buf.get_i16_le();
18474 __struct.press_diff1 = buf.get_i16_le();
18475 __struct.press_diff2 = buf.get_i16_le();
18476 __struct.temperature = buf.get_i16_le();
18477 Ok(__struct)
18478 }
18479 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18480 let mut __tmp = BytesMut::new(bytes);
18481 #[allow(clippy::absurd_extreme_comparisons)]
18482 #[allow(unused_comparisons)]
18483 if __tmp.remaining() < Self::ENCODED_LEN {
18484 panic!(
18485 "buffer is too small (need {} bytes, but got {})",
18486 Self::ENCODED_LEN,
18487 __tmp.remaining(),
18488 )
18489 }
18490 __tmp.put_u64_le(self.time_usec);
18491 __tmp.put_i16_le(self.press_abs);
18492 __tmp.put_i16_le(self.press_diff1);
18493 __tmp.put_i16_le(self.press_diff2);
18494 __tmp.put_i16_le(self.temperature);
18495 if matches!(version, MavlinkVersion::V2) {
18496 let len = __tmp.len();
18497 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18498 } else {
18499 __tmp.len()
18500 }
18501 }
18502}
18503#[doc = "id: 12902"]
18504#[doc = "Data for filling the OpenDroneID Authentication message. The Authentication Message defines a field that can provide a means of authenticity for the identity of the UAS (Unmanned Aircraft System). The Authentication message can have two different formats. For data page 0, the fields PageCount, Length and TimeStamp are present and AuthData is only 17 bytes. For data page 1 through 15, PageCount, Length and TimeStamp are not present and the size of AuthData is 23 bytes."]
18505#[derive(Debug, Clone, PartialEq)]
18506#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18507#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18508pub struct OPEN_DRONE_ID_AUTHENTICATION_DATA {
18509 #[doc = "This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
18510 pub timestamp: u32,
18511 #[doc = "System ID (0 for broadcast)."]
18512 pub target_system: u8,
18513 #[doc = "Component ID (0 for broadcast)."]
18514 pub target_component: u8,
18515 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
18516 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18517 pub id_or_mac: [u8; 20],
18518 #[doc = "Indicates the type of authentication."]
18519 pub authentication_type: MavOdidAuthType,
18520 #[doc = "Allowed range is 0 - 15."]
18521 pub data_page: u8,
18522 #[doc = "This field is only present for page 0. Allowed range is 0 - 15. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
18523 pub last_page_index: u8,
18524 #[doc = "This field is only present for page 0. Total bytes of authentication_data from all data pages. See the description of struct ODID_Auth_data at <https://github.com/opendroneid/opendroneid-core-c/blob/master/libopendroneid/opendroneid.h>."]
18525 pub length: u8,
18526 #[doc = "Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field."]
18527 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18528 pub authentication_data: [u8; 23],
18529}
18530impl OPEN_DRONE_ID_AUTHENTICATION_DATA {
18531 pub const ENCODED_LEN: usize = 53usize;
18532 pub const DEFAULT: Self = Self {
18533 timestamp: 0_u32,
18534 target_system: 0_u8,
18535 target_component: 0_u8,
18536 id_or_mac: [0_u8; 20usize],
18537 authentication_type: MavOdidAuthType::DEFAULT,
18538 data_page: 0_u8,
18539 last_page_index: 0_u8,
18540 length: 0_u8,
18541 authentication_data: [0_u8; 23usize],
18542 };
18543 #[cfg(feature = "arbitrary")]
18544 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18545 use arbitrary::{Arbitrary, Unstructured};
18546 let mut buf = [0u8; 1024];
18547 rng.fill_bytes(&mut buf);
18548 let mut unstructured = Unstructured::new(&buf);
18549 Self::arbitrary(&mut unstructured).unwrap_or_default()
18550 }
18551}
18552impl Default for OPEN_DRONE_ID_AUTHENTICATION_DATA {
18553 fn default() -> Self {
18554 Self::DEFAULT.clone()
18555 }
18556}
18557impl MessageData for OPEN_DRONE_ID_AUTHENTICATION_DATA {
18558 type Message = MavMessage;
18559 const ID: u32 = 12902u32;
18560 const NAME: &'static str = "OPEN_DRONE_ID_AUTHENTICATION";
18561 const EXTRA_CRC: u8 = 140u8;
18562 const ENCODED_LEN: usize = 53usize;
18563 fn deser(
18564 _version: MavlinkVersion,
18565 __input: &[u8],
18566 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18567 let avail_len = __input.len();
18568 let mut payload_buf = [0; Self::ENCODED_LEN];
18569 let mut buf = if avail_len < Self::ENCODED_LEN {
18570 payload_buf[0..avail_len].copy_from_slice(__input);
18571 Bytes::new(&payload_buf)
18572 } else {
18573 Bytes::new(__input)
18574 };
18575 let mut __struct = Self::default();
18576 __struct.timestamp = buf.get_u32_le();
18577 __struct.target_system = buf.get_u8();
18578 __struct.target_component = buf.get_u8();
18579 for v in &mut __struct.id_or_mac {
18580 let val = buf.get_u8();
18581 *v = val;
18582 }
18583 let tmp = buf.get_u8();
18584 __struct.authentication_type =
18585 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18586 enum_type: "MavOdidAuthType",
18587 value: tmp as u32,
18588 })?;
18589 __struct.data_page = buf.get_u8();
18590 __struct.last_page_index = buf.get_u8();
18591 __struct.length = buf.get_u8();
18592 for v in &mut __struct.authentication_data {
18593 let val = buf.get_u8();
18594 *v = val;
18595 }
18596 Ok(__struct)
18597 }
18598 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18599 let mut __tmp = BytesMut::new(bytes);
18600 #[allow(clippy::absurd_extreme_comparisons)]
18601 #[allow(unused_comparisons)]
18602 if __tmp.remaining() < Self::ENCODED_LEN {
18603 panic!(
18604 "buffer is too small (need {} bytes, but got {})",
18605 Self::ENCODED_LEN,
18606 __tmp.remaining(),
18607 )
18608 }
18609 __tmp.put_u32_le(self.timestamp);
18610 __tmp.put_u8(self.target_system);
18611 __tmp.put_u8(self.target_component);
18612 for val in &self.id_or_mac {
18613 __tmp.put_u8(*val);
18614 }
18615 __tmp.put_u8(self.authentication_type as u8);
18616 __tmp.put_u8(self.data_page);
18617 __tmp.put_u8(self.last_page_index);
18618 __tmp.put_u8(self.length);
18619 for val in &self.authentication_data {
18620 __tmp.put_u8(*val);
18621 }
18622 if matches!(version, MavlinkVersion::V2) {
18623 let len = __tmp.len();
18624 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18625 } else {
18626 __tmp.len()
18627 }
18628 }
18629}
18630#[doc = "id: 290"]
18631#[doc = "ESC information for lower rate streaming. Recommended streaming rate 1Hz. See ESC_STATUS for higher-rate ESC data."]
18632#[derive(Debug, Clone, PartialEq)]
18633#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18634#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18635pub struct ESC_INFO_DATA {
18636 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
18637 pub time_usec: u64,
18638 #[doc = "Number of reported errors by each ESC since boot."]
18639 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18640 pub error_count: [u32; 4],
18641 #[doc = "Counter of data packets received."]
18642 pub counter: u16,
18643 #[doc = "Bitmap of ESC failure flags."]
18644 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18645 pub failure_flags: [u16; 4],
18646 #[doc = "Temperature of each ESC. INT16_MAX: if data not supplied by ESC."]
18647 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18648 pub temperature: [i16; 4],
18649 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
18650 pub index: u8,
18651 #[doc = "Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data."]
18652 pub count: u8,
18653 #[doc = "Connection type protocol for all ESC."]
18654 pub connection_type: EscConnectionType,
18655 #[doc = "Information regarding online/offline status of each ESC."]
18656 pub info: u8,
18657}
18658impl ESC_INFO_DATA {
18659 pub const ENCODED_LEN: usize = 46usize;
18660 pub const DEFAULT: Self = Self {
18661 time_usec: 0_u64,
18662 error_count: [0_u32; 4usize],
18663 counter: 0_u16,
18664 failure_flags: [0_u16; 4usize],
18665 temperature: [0_i16; 4usize],
18666 index: 0_u8,
18667 count: 0_u8,
18668 connection_type: EscConnectionType::DEFAULT,
18669 info: 0_u8,
18670 };
18671 #[cfg(feature = "arbitrary")]
18672 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18673 use arbitrary::{Arbitrary, Unstructured};
18674 let mut buf = [0u8; 1024];
18675 rng.fill_bytes(&mut buf);
18676 let mut unstructured = Unstructured::new(&buf);
18677 Self::arbitrary(&mut unstructured).unwrap_or_default()
18678 }
18679}
18680impl Default for ESC_INFO_DATA {
18681 fn default() -> Self {
18682 Self::DEFAULT.clone()
18683 }
18684}
18685impl MessageData for ESC_INFO_DATA {
18686 type Message = MavMessage;
18687 const ID: u32 = 290u32;
18688 const NAME: &'static str = "ESC_INFO";
18689 const EXTRA_CRC: u8 = 251u8;
18690 const ENCODED_LEN: usize = 46usize;
18691 fn deser(
18692 _version: MavlinkVersion,
18693 __input: &[u8],
18694 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18695 let avail_len = __input.len();
18696 let mut payload_buf = [0; Self::ENCODED_LEN];
18697 let mut buf = if avail_len < Self::ENCODED_LEN {
18698 payload_buf[0..avail_len].copy_from_slice(__input);
18699 Bytes::new(&payload_buf)
18700 } else {
18701 Bytes::new(__input)
18702 };
18703 let mut __struct = Self::default();
18704 __struct.time_usec = buf.get_u64_le();
18705 for v in &mut __struct.error_count {
18706 let val = buf.get_u32_le();
18707 *v = val;
18708 }
18709 __struct.counter = buf.get_u16_le();
18710 for v in &mut __struct.failure_flags {
18711 let val = buf.get_u16_le();
18712 *v = val;
18713 }
18714 for v in &mut __struct.temperature {
18715 let val = buf.get_i16_le();
18716 *v = val;
18717 }
18718 __struct.index = buf.get_u8();
18719 __struct.count = buf.get_u8();
18720 let tmp = buf.get_u8();
18721 __struct.connection_type =
18722 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18723 enum_type: "EscConnectionType",
18724 value: tmp as u32,
18725 })?;
18726 __struct.info = buf.get_u8();
18727 Ok(__struct)
18728 }
18729 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18730 let mut __tmp = BytesMut::new(bytes);
18731 #[allow(clippy::absurd_extreme_comparisons)]
18732 #[allow(unused_comparisons)]
18733 if __tmp.remaining() < Self::ENCODED_LEN {
18734 panic!(
18735 "buffer is too small (need {} bytes, but got {})",
18736 Self::ENCODED_LEN,
18737 __tmp.remaining(),
18738 )
18739 }
18740 __tmp.put_u64_le(self.time_usec);
18741 for val in &self.error_count {
18742 __tmp.put_u32_le(*val);
18743 }
18744 __tmp.put_u16_le(self.counter);
18745 for val in &self.failure_flags {
18746 __tmp.put_u16_le(*val);
18747 }
18748 for val in &self.temperature {
18749 __tmp.put_i16_le(*val);
18750 }
18751 __tmp.put_u8(self.index);
18752 __tmp.put_u8(self.count);
18753 __tmp.put_u8(self.connection_type as u8);
18754 __tmp.put_u8(self.info);
18755 if matches!(version, MavlinkVersion::V2) {
18756 let len = __tmp.len();
18757 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18758 } else {
18759 __tmp.len()
18760 }
18761 }
18762}
18763#[doc = "id: 132"]
18764#[doc = "Distance sensor information for an onboard rangefinder."]
18765#[derive(Debug, Clone, PartialEq)]
18766#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18767#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18768pub struct DISTANCE_SENSOR_DATA {
18769 #[doc = "Timestamp (time since system boot)."]
18770 pub time_boot_ms: u32,
18771 #[doc = "Minimum distance the sensor can measure"]
18772 pub min_distance: u16,
18773 #[doc = "Maximum distance the sensor can measure"]
18774 pub max_distance: u16,
18775 #[doc = "Current distance reading"]
18776 pub current_distance: u16,
18777 #[doc = "Type of distance sensor."]
18778 pub mavtype: MavDistanceSensor,
18779 #[doc = "Onboard ID of the sensor"]
18780 pub id: u8,
18781 #[doc = "Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270"]
18782 pub orientation: MavSensorOrientation,
18783 #[doc = "Measurement variance. Max standard deviation is 6cm. UINT8_MAX if unknown."]
18784 pub covariance: u8,
18785 #[doc = "Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
18786 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18787 pub horizontal_fov: f32,
18788 #[doc = "Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0."]
18789 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18790 pub vertical_fov: f32,
18791 #[doc = "Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid.\""]
18792 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18793 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
18794 pub quaternion: [f32; 4],
18795 #[doc = "Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal."]
18796 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
18797 pub signal_quality: u8,
18798}
18799impl DISTANCE_SENSOR_DATA {
18800 pub const ENCODED_LEN: usize = 39usize;
18801 pub const DEFAULT: Self = Self {
18802 time_boot_ms: 0_u32,
18803 min_distance: 0_u16,
18804 max_distance: 0_u16,
18805 current_distance: 0_u16,
18806 mavtype: MavDistanceSensor::DEFAULT,
18807 id: 0_u8,
18808 orientation: MavSensorOrientation::DEFAULT,
18809 covariance: 0_u8,
18810 horizontal_fov: 0.0_f32,
18811 vertical_fov: 0.0_f32,
18812 quaternion: [0.0_f32; 4usize],
18813 signal_quality: 0_u8,
18814 };
18815 #[cfg(feature = "arbitrary")]
18816 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18817 use arbitrary::{Arbitrary, Unstructured};
18818 let mut buf = [0u8; 1024];
18819 rng.fill_bytes(&mut buf);
18820 let mut unstructured = Unstructured::new(&buf);
18821 Self::arbitrary(&mut unstructured).unwrap_or_default()
18822 }
18823}
18824impl Default for DISTANCE_SENSOR_DATA {
18825 fn default() -> Self {
18826 Self::DEFAULT.clone()
18827 }
18828}
18829impl MessageData for DISTANCE_SENSOR_DATA {
18830 type Message = MavMessage;
18831 const ID: u32 = 132u32;
18832 const NAME: &'static str = "DISTANCE_SENSOR";
18833 const EXTRA_CRC: u8 = 85u8;
18834 const ENCODED_LEN: usize = 39usize;
18835 fn deser(
18836 _version: MavlinkVersion,
18837 __input: &[u8],
18838 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18839 let avail_len = __input.len();
18840 let mut payload_buf = [0; Self::ENCODED_LEN];
18841 let mut buf = if avail_len < Self::ENCODED_LEN {
18842 payload_buf[0..avail_len].copy_from_slice(__input);
18843 Bytes::new(&payload_buf)
18844 } else {
18845 Bytes::new(__input)
18846 };
18847 let mut __struct = Self::default();
18848 __struct.time_boot_ms = buf.get_u32_le();
18849 __struct.min_distance = buf.get_u16_le();
18850 __struct.max_distance = buf.get_u16_le();
18851 __struct.current_distance = buf.get_u16_le();
18852 let tmp = buf.get_u8();
18853 __struct.mavtype =
18854 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18855 enum_type: "MavDistanceSensor",
18856 value: tmp as u32,
18857 })?;
18858 __struct.id = buf.get_u8();
18859 let tmp = buf.get_u8();
18860 __struct.orientation =
18861 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
18862 enum_type: "MavSensorOrientation",
18863 value: tmp as u32,
18864 })?;
18865 __struct.covariance = buf.get_u8();
18866 __struct.horizontal_fov = buf.get_f32_le();
18867 __struct.vertical_fov = buf.get_f32_le();
18868 for v in &mut __struct.quaternion {
18869 let val = buf.get_f32_le();
18870 *v = val;
18871 }
18872 __struct.signal_quality = buf.get_u8();
18873 Ok(__struct)
18874 }
18875 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
18876 let mut __tmp = BytesMut::new(bytes);
18877 #[allow(clippy::absurd_extreme_comparisons)]
18878 #[allow(unused_comparisons)]
18879 if __tmp.remaining() < Self::ENCODED_LEN {
18880 panic!(
18881 "buffer is too small (need {} bytes, but got {})",
18882 Self::ENCODED_LEN,
18883 __tmp.remaining(),
18884 )
18885 }
18886 __tmp.put_u32_le(self.time_boot_ms);
18887 __tmp.put_u16_le(self.min_distance);
18888 __tmp.put_u16_le(self.max_distance);
18889 __tmp.put_u16_le(self.current_distance);
18890 __tmp.put_u8(self.mavtype as u8);
18891 __tmp.put_u8(self.id);
18892 __tmp.put_u8(self.orientation as u8);
18893 __tmp.put_u8(self.covariance);
18894 __tmp.put_f32_le(self.horizontal_fov);
18895 __tmp.put_f32_le(self.vertical_fov);
18896 for val in &self.quaternion {
18897 __tmp.put_f32_le(*val);
18898 }
18899 __tmp.put_u8(self.signal_quality);
18900 if matches!(version, MavlinkVersion::V2) {
18901 let len = __tmp.len();
18902 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
18903 } else {
18904 __tmp.len()
18905 }
18906 }
18907}
18908#[doc = "id: 92"]
18909#[doc = "Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification."]
18910#[derive(Debug, Clone, PartialEq)]
18911#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
18912#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
18913pub struct HIL_RC_INPUTS_RAW_DATA {
18914 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
18915 pub time_usec: u64,
18916 #[doc = "RC channel 1 value"]
18917 pub chan1_raw: u16,
18918 #[doc = "RC channel 2 value"]
18919 pub chan2_raw: u16,
18920 #[doc = "RC channel 3 value"]
18921 pub chan3_raw: u16,
18922 #[doc = "RC channel 4 value"]
18923 pub chan4_raw: u16,
18924 #[doc = "RC channel 5 value"]
18925 pub chan5_raw: u16,
18926 #[doc = "RC channel 6 value"]
18927 pub chan6_raw: u16,
18928 #[doc = "RC channel 7 value"]
18929 pub chan7_raw: u16,
18930 #[doc = "RC channel 8 value"]
18931 pub chan8_raw: u16,
18932 #[doc = "RC channel 9 value"]
18933 pub chan9_raw: u16,
18934 #[doc = "RC channel 10 value"]
18935 pub chan10_raw: u16,
18936 #[doc = "RC channel 11 value"]
18937 pub chan11_raw: u16,
18938 #[doc = "RC channel 12 value"]
18939 pub chan12_raw: u16,
18940 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
18941 pub rssi: u8,
18942}
18943impl HIL_RC_INPUTS_RAW_DATA {
18944 pub const ENCODED_LEN: usize = 33usize;
18945 pub const DEFAULT: Self = Self {
18946 time_usec: 0_u64,
18947 chan1_raw: 0_u16,
18948 chan2_raw: 0_u16,
18949 chan3_raw: 0_u16,
18950 chan4_raw: 0_u16,
18951 chan5_raw: 0_u16,
18952 chan6_raw: 0_u16,
18953 chan7_raw: 0_u16,
18954 chan8_raw: 0_u16,
18955 chan9_raw: 0_u16,
18956 chan10_raw: 0_u16,
18957 chan11_raw: 0_u16,
18958 chan12_raw: 0_u16,
18959 rssi: 0_u8,
18960 };
18961 #[cfg(feature = "arbitrary")]
18962 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
18963 use arbitrary::{Arbitrary, Unstructured};
18964 let mut buf = [0u8; 1024];
18965 rng.fill_bytes(&mut buf);
18966 let mut unstructured = Unstructured::new(&buf);
18967 Self::arbitrary(&mut unstructured).unwrap_or_default()
18968 }
18969}
18970impl Default for HIL_RC_INPUTS_RAW_DATA {
18971 fn default() -> Self {
18972 Self::DEFAULT.clone()
18973 }
18974}
18975impl MessageData for HIL_RC_INPUTS_RAW_DATA {
18976 type Message = MavMessage;
18977 const ID: u32 = 92u32;
18978 const NAME: &'static str = "HIL_RC_INPUTS_RAW";
18979 const EXTRA_CRC: u8 = 54u8;
18980 const ENCODED_LEN: usize = 33usize;
18981 fn deser(
18982 _version: MavlinkVersion,
18983 __input: &[u8],
18984 ) -> Result<Self, ::mavlink_core::error::ParserError> {
18985 let avail_len = __input.len();
18986 let mut payload_buf = [0; Self::ENCODED_LEN];
18987 let mut buf = if avail_len < Self::ENCODED_LEN {
18988 payload_buf[0..avail_len].copy_from_slice(__input);
18989 Bytes::new(&payload_buf)
18990 } else {
18991 Bytes::new(__input)
18992 };
18993 let mut __struct = Self::default();
18994 __struct.time_usec = buf.get_u64_le();
18995 __struct.chan1_raw = buf.get_u16_le();
18996 __struct.chan2_raw = buf.get_u16_le();
18997 __struct.chan3_raw = buf.get_u16_le();
18998 __struct.chan4_raw = buf.get_u16_le();
18999 __struct.chan5_raw = buf.get_u16_le();
19000 __struct.chan6_raw = buf.get_u16_le();
19001 __struct.chan7_raw = buf.get_u16_le();
19002 __struct.chan8_raw = buf.get_u16_le();
19003 __struct.chan9_raw = buf.get_u16_le();
19004 __struct.chan10_raw = buf.get_u16_le();
19005 __struct.chan11_raw = buf.get_u16_le();
19006 __struct.chan12_raw = buf.get_u16_le();
19007 __struct.rssi = buf.get_u8();
19008 Ok(__struct)
19009 }
19010 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19011 let mut __tmp = BytesMut::new(bytes);
19012 #[allow(clippy::absurd_extreme_comparisons)]
19013 #[allow(unused_comparisons)]
19014 if __tmp.remaining() < Self::ENCODED_LEN {
19015 panic!(
19016 "buffer is too small (need {} bytes, but got {})",
19017 Self::ENCODED_LEN,
19018 __tmp.remaining(),
19019 )
19020 }
19021 __tmp.put_u64_le(self.time_usec);
19022 __tmp.put_u16_le(self.chan1_raw);
19023 __tmp.put_u16_le(self.chan2_raw);
19024 __tmp.put_u16_le(self.chan3_raw);
19025 __tmp.put_u16_le(self.chan4_raw);
19026 __tmp.put_u16_le(self.chan5_raw);
19027 __tmp.put_u16_le(self.chan6_raw);
19028 __tmp.put_u16_le(self.chan7_raw);
19029 __tmp.put_u16_le(self.chan8_raw);
19030 __tmp.put_u16_le(self.chan9_raw);
19031 __tmp.put_u16_le(self.chan10_raw);
19032 __tmp.put_u16_le(self.chan11_raw);
19033 __tmp.put_u16_le(self.chan12_raw);
19034 __tmp.put_u8(self.rssi);
19035 if matches!(version, MavlinkVersion::V2) {
19036 let len = __tmp.len();
19037 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19038 } else {
19039 __tmp.len()
19040 }
19041 }
19042}
19043#[doc = "id: 335"]
19044#[doc = "Status of the Iridium SBD link."]
19045#[derive(Debug, Clone, PartialEq)]
19046#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19047#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19048pub struct ISBD_LINK_STATUS_DATA {
19049 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19050 pub timestamp: u64,
19051 #[doc = "Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19052 pub last_heartbeat: u64,
19053 #[doc = "Number of failed SBD sessions."]
19054 pub failed_sessions: u16,
19055 #[doc = "Number of successful SBD sessions."]
19056 pub successful_sessions: u16,
19057 #[doc = "Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength."]
19058 pub signal_quality: u8,
19059 #[doc = "1: Ring call pending, 0: No call pending."]
19060 pub ring_pending: u8,
19061 #[doc = "1: Transmission session pending, 0: No transmission session pending."]
19062 pub tx_session_pending: u8,
19063 #[doc = "1: Receiving session pending, 0: No receiving session pending."]
19064 pub rx_session_pending: u8,
19065}
19066impl ISBD_LINK_STATUS_DATA {
19067 pub const ENCODED_LEN: usize = 24usize;
19068 pub const DEFAULT: Self = Self {
19069 timestamp: 0_u64,
19070 last_heartbeat: 0_u64,
19071 failed_sessions: 0_u16,
19072 successful_sessions: 0_u16,
19073 signal_quality: 0_u8,
19074 ring_pending: 0_u8,
19075 tx_session_pending: 0_u8,
19076 rx_session_pending: 0_u8,
19077 };
19078 #[cfg(feature = "arbitrary")]
19079 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19080 use arbitrary::{Arbitrary, Unstructured};
19081 let mut buf = [0u8; 1024];
19082 rng.fill_bytes(&mut buf);
19083 let mut unstructured = Unstructured::new(&buf);
19084 Self::arbitrary(&mut unstructured).unwrap_or_default()
19085 }
19086}
19087impl Default for ISBD_LINK_STATUS_DATA {
19088 fn default() -> Self {
19089 Self::DEFAULT.clone()
19090 }
19091}
19092impl MessageData for ISBD_LINK_STATUS_DATA {
19093 type Message = MavMessage;
19094 const ID: u32 = 335u32;
19095 const NAME: &'static str = "ISBD_LINK_STATUS";
19096 const EXTRA_CRC: u8 = 225u8;
19097 const ENCODED_LEN: usize = 24usize;
19098 fn deser(
19099 _version: MavlinkVersion,
19100 __input: &[u8],
19101 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19102 let avail_len = __input.len();
19103 let mut payload_buf = [0; Self::ENCODED_LEN];
19104 let mut buf = if avail_len < Self::ENCODED_LEN {
19105 payload_buf[0..avail_len].copy_from_slice(__input);
19106 Bytes::new(&payload_buf)
19107 } else {
19108 Bytes::new(__input)
19109 };
19110 let mut __struct = Self::default();
19111 __struct.timestamp = buf.get_u64_le();
19112 __struct.last_heartbeat = buf.get_u64_le();
19113 __struct.failed_sessions = buf.get_u16_le();
19114 __struct.successful_sessions = buf.get_u16_le();
19115 __struct.signal_quality = buf.get_u8();
19116 __struct.ring_pending = buf.get_u8();
19117 __struct.tx_session_pending = buf.get_u8();
19118 __struct.rx_session_pending = buf.get_u8();
19119 Ok(__struct)
19120 }
19121 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19122 let mut __tmp = BytesMut::new(bytes);
19123 #[allow(clippy::absurd_extreme_comparisons)]
19124 #[allow(unused_comparisons)]
19125 if __tmp.remaining() < Self::ENCODED_LEN {
19126 panic!(
19127 "buffer is too small (need {} bytes, but got {})",
19128 Self::ENCODED_LEN,
19129 __tmp.remaining(),
19130 )
19131 }
19132 __tmp.put_u64_le(self.timestamp);
19133 __tmp.put_u64_le(self.last_heartbeat);
19134 __tmp.put_u16_le(self.failed_sessions);
19135 __tmp.put_u16_le(self.successful_sessions);
19136 __tmp.put_u8(self.signal_quality);
19137 __tmp.put_u8(self.ring_pending);
19138 __tmp.put_u8(self.tx_session_pending);
19139 __tmp.put_u8(self.rx_session_pending);
19140 if matches!(version, MavlinkVersion::V2) {
19141 let len = __tmp.len();
19142 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19143 } else {
19144 __tmp.len()
19145 }
19146 }
19147}
19148#[doc = "id: 34"]
19149#[doc = "The scaled values of the RC channels received: (-100%) -10000, (0%) 0, (100%) 10000. Channels that are inactive should be set to INT16_MAX."]
19150#[derive(Debug, Clone, PartialEq)]
19151#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19152#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19153pub struct RC_CHANNELS_SCALED_DATA {
19154 #[doc = "Timestamp (time since system boot)."]
19155 pub time_boot_ms: u32,
19156 #[doc = "RC channel 1 value scaled."]
19157 pub chan1_scaled: i16,
19158 #[doc = "RC channel 2 value scaled."]
19159 pub chan2_scaled: i16,
19160 #[doc = "RC channel 3 value scaled."]
19161 pub chan3_scaled: i16,
19162 #[doc = "RC channel 4 value scaled."]
19163 pub chan4_scaled: i16,
19164 #[doc = "RC channel 5 value scaled."]
19165 pub chan5_scaled: i16,
19166 #[doc = "RC channel 6 value scaled."]
19167 pub chan6_scaled: i16,
19168 #[doc = "RC channel 7 value scaled."]
19169 pub chan7_scaled: i16,
19170 #[doc = "RC channel 8 value scaled."]
19171 pub chan8_scaled: i16,
19172 #[doc = "Servo output port (set of 8 outputs = 1 port). Flight stacks running on Pixhawk should use: 0 = MAIN, 1 = AUX."]
19173 pub port: u8,
19174 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
19175 pub rssi: u8,
19176}
19177impl RC_CHANNELS_SCALED_DATA {
19178 pub const ENCODED_LEN: usize = 22usize;
19179 pub const DEFAULT: Self = Self {
19180 time_boot_ms: 0_u32,
19181 chan1_scaled: 0_i16,
19182 chan2_scaled: 0_i16,
19183 chan3_scaled: 0_i16,
19184 chan4_scaled: 0_i16,
19185 chan5_scaled: 0_i16,
19186 chan6_scaled: 0_i16,
19187 chan7_scaled: 0_i16,
19188 chan8_scaled: 0_i16,
19189 port: 0_u8,
19190 rssi: 0_u8,
19191 };
19192 #[cfg(feature = "arbitrary")]
19193 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19194 use arbitrary::{Arbitrary, Unstructured};
19195 let mut buf = [0u8; 1024];
19196 rng.fill_bytes(&mut buf);
19197 let mut unstructured = Unstructured::new(&buf);
19198 Self::arbitrary(&mut unstructured).unwrap_or_default()
19199 }
19200}
19201impl Default for RC_CHANNELS_SCALED_DATA {
19202 fn default() -> Self {
19203 Self::DEFAULT.clone()
19204 }
19205}
19206impl MessageData for RC_CHANNELS_SCALED_DATA {
19207 type Message = MavMessage;
19208 const ID: u32 = 34u32;
19209 const NAME: &'static str = "RC_CHANNELS_SCALED";
19210 const EXTRA_CRC: u8 = 237u8;
19211 const ENCODED_LEN: usize = 22usize;
19212 fn deser(
19213 _version: MavlinkVersion,
19214 __input: &[u8],
19215 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19216 let avail_len = __input.len();
19217 let mut payload_buf = [0; Self::ENCODED_LEN];
19218 let mut buf = if avail_len < Self::ENCODED_LEN {
19219 payload_buf[0..avail_len].copy_from_slice(__input);
19220 Bytes::new(&payload_buf)
19221 } else {
19222 Bytes::new(__input)
19223 };
19224 let mut __struct = Self::default();
19225 __struct.time_boot_ms = buf.get_u32_le();
19226 __struct.chan1_scaled = buf.get_i16_le();
19227 __struct.chan2_scaled = buf.get_i16_le();
19228 __struct.chan3_scaled = buf.get_i16_le();
19229 __struct.chan4_scaled = buf.get_i16_le();
19230 __struct.chan5_scaled = buf.get_i16_le();
19231 __struct.chan6_scaled = buf.get_i16_le();
19232 __struct.chan7_scaled = buf.get_i16_le();
19233 __struct.chan8_scaled = buf.get_i16_le();
19234 __struct.port = buf.get_u8();
19235 __struct.rssi = buf.get_u8();
19236 Ok(__struct)
19237 }
19238 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19239 let mut __tmp = BytesMut::new(bytes);
19240 #[allow(clippy::absurd_extreme_comparisons)]
19241 #[allow(unused_comparisons)]
19242 if __tmp.remaining() < Self::ENCODED_LEN {
19243 panic!(
19244 "buffer is too small (need {} bytes, but got {})",
19245 Self::ENCODED_LEN,
19246 __tmp.remaining(),
19247 )
19248 }
19249 __tmp.put_u32_le(self.time_boot_ms);
19250 __tmp.put_i16_le(self.chan1_scaled);
19251 __tmp.put_i16_le(self.chan2_scaled);
19252 __tmp.put_i16_le(self.chan3_scaled);
19253 __tmp.put_i16_le(self.chan4_scaled);
19254 __tmp.put_i16_le(self.chan5_scaled);
19255 __tmp.put_i16_le(self.chan6_scaled);
19256 __tmp.put_i16_le(self.chan7_scaled);
19257 __tmp.put_i16_le(self.chan8_scaled);
19258 __tmp.put_u8(self.port);
19259 __tmp.put_u8(self.rssi);
19260 if matches!(version, MavlinkVersion::V2) {
19261 let len = __tmp.len();
19262 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19263 } else {
19264 __tmp.len()
19265 }
19266 }
19267}
19268#[doc = "id: 116"]
19269#[doc = "The RAW IMU readings for secondary 9DOF sensor setup. This message should contain the scaled values to the described units."]
19270#[derive(Debug, Clone, PartialEq)]
19271#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19272#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19273pub struct SCALED_IMU2_DATA {
19274 #[doc = "Timestamp (time since system boot)."]
19275 pub time_boot_ms: u32,
19276 #[doc = "X acceleration"]
19277 pub xacc: i16,
19278 #[doc = "Y acceleration"]
19279 pub yacc: i16,
19280 #[doc = "Z acceleration"]
19281 pub zacc: i16,
19282 #[doc = "Angular speed around X axis"]
19283 pub xgyro: i16,
19284 #[doc = "Angular speed around Y axis"]
19285 pub ygyro: i16,
19286 #[doc = "Angular speed around Z axis"]
19287 pub zgyro: i16,
19288 #[doc = "X Magnetic field"]
19289 pub xmag: i16,
19290 #[doc = "Y Magnetic field"]
19291 pub ymag: i16,
19292 #[doc = "Z Magnetic field"]
19293 pub zmag: i16,
19294 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
19295 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19296 pub temperature: i16,
19297}
19298impl SCALED_IMU2_DATA {
19299 pub const ENCODED_LEN: usize = 24usize;
19300 pub const DEFAULT: Self = Self {
19301 time_boot_ms: 0_u32,
19302 xacc: 0_i16,
19303 yacc: 0_i16,
19304 zacc: 0_i16,
19305 xgyro: 0_i16,
19306 ygyro: 0_i16,
19307 zgyro: 0_i16,
19308 xmag: 0_i16,
19309 ymag: 0_i16,
19310 zmag: 0_i16,
19311 temperature: 0_i16,
19312 };
19313 #[cfg(feature = "arbitrary")]
19314 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19315 use arbitrary::{Arbitrary, Unstructured};
19316 let mut buf = [0u8; 1024];
19317 rng.fill_bytes(&mut buf);
19318 let mut unstructured = Unstructured::new(&buf);
19319 Self::arbitrary(&mut unstructured).unwrap_or_default()
19320 }
19321}
19322impl Default for SCALED_IMU2_DATA {
19323 fn default() -> Self {
19324 Self::DEFAULT.clone()
19325 }
19326}
19327impl MessageData for SCALED_IMU2_DATA {
19328 type Message = MavMessage;
19329 const ID: u32 = 116u32;
19330 const NAME: &'static str = "SCALED_IMU2";
19331 const EXTRA_CRC: u8 = 76u8;
19332 const ENCODED_LEN: usize = 24usize;
19333 fn deser(
19334 _version: MavlinkVersion,
19335 __input: &[u8],
19336 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19337 let avail_len = __input.len();
19338 let mut payload_buf = [0; Self::ENCODED_LEN];
19339 let mut buf = if avail_len < Self::ENCODED_LEN {
19340 payload_buf[0..avail_len].copy_from_slice(__input);
19341 Bytes::new(&payload_buf)
19342 } else {
19343 Bytes::new(__input)
19344 };
19345 let mut __struct = Self::default();
19346 __struct.time_boot_ms = buf.get_u32_le();
19347 __struct.xacc = buf.get_i16_le();
19348 __struct.yacc = buf.get_i16_le();
19349 __struct.zacc = buf.get_i16_le();
19350 __struct.xgyro = buf.get_i16_le();
19351 __struct.ygyro = buf.get_i16_le();
19352 __struct.zgyro = buf.get_i16_le();
19353 __struct.xmag = buf.get_i16_le();
19354 __struct.ymag = buf.get_i16_le();
19355 __struct.zmag = buf.get_i16_le();
19356 __struct.temperature = buf.get_i16_le();
19357 Ok(__struct)
19358 }
19359 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19360 let mut __tmp = BytesMut::new(bytes);
19361 #[allow(clippy::absurd_extreme_comparisons)]
19362 #[allow(unused_comparisons)]
19363 if __tmp.remaining() < Self::ENCODED_LEN {
19364 panic!(
19365 "buffer is too small (need {} bytes, but got {})",
19366 Self::ENCODED_LEN,
19367 __tmp.remaining(),
19368 )
19369 }
19370 __tmp.put_u32_le(self.time_boot_ms);
19371 __tmp.put_i16_le(self.xacc);
19372 __tmp.put_i16_le(self.yacc);
19373 __tmp.put_i16_le(self.zacc);
19374 __tmp.put_i16_le(self.xgyro);
19375 __tmp.put_i16_le(self.ygyro);
19376 __tmp.put_i16_le(self.zgyro);
19377 __tmp.put_i16_le(self.xmag);
19378 __tmp.put_i16_le(self.ymag);
19379 __tmp.put_i16_le(self.zmag);
19380 __tmp.put_i16_le(self.temperature);
19381 if matches!(version, MavlinkVersion::V2) {
19382 let len = __tmp.len();
19383 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19384 } else {
19385 __tmp.len()
19386 }
19387 }
19388}
19389#[doc = "id: 107"]
19390#[doc = "The IMU readings in SI units in NED body frame."]
19391#[derive(Debug, Clone, PartialEq)]
19392#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19393#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19394pub struct HIL_SENSOR_DATA {
19395 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
19396 pub time_usec: u64,
19397 #[doc = "X acceleration"]
19398 pub xacc: f32,
19399 #[doc = "Y acceleration"]
19400 pub yacc: f32,
19401 #[doc = "Z acceleration"]
19402 pub zacc: f32,
19403 #[doc = "Angular speed around X axis in body frame"]
19404 pub xgyro: f32,
19405 #[doc = "Angular speed around Y axis in body frame"]
19406 pub ygyro: f32,
19407 #[doc = "Angular speed around Z axis in body frame"]
19408 pub zgyro: f32,
19409 #[doc = "X Magnetic field"]
19410 pub xmag: f32,
19411 #[doc = "Y Magnetic field"]
19412 pub ymag: f32,
19413 #[doc = "Z Magnetic field"]
19414 pub zmag: f32,
19415 #[doc = "Absolute pressure"]
19416 pub abs_pressure: f32,
19417 #[doc = "Differential pressure (airspeed)"]
19418 pub diff_pressure: f32,
19419 #[doc = "Altitude calculated from pressure"]
19420 pub pressure_alt: f32,
19421 #[doc = "Temperature"]
19422 pub temperature: f32,
19423 #[doc = "Bitmap for fields that have updated since last message"]
19424 pub fields_updated: HilSensorUpdatedFlags,
19425 #[doc = "Sensor ID (zero indexed). Used for multiple sensor inputs"]
19426 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19427 pub id: u8,
19428}
19429impl HIL_SENSOR_DATA {
19430 pub const ENCODED_LEN: usize = 65usize;
19431 pub const DEFAULT: Self = Self {
19432 time_usec: 0_u64,
19433 xacc: 0.0_f32,
19434 yacc: 0.0_f32,
19435 zacc: 0.0_f32,
19436 xgyro: 0.0_f32,
19437 ygyro: 0.0_f32,
19438 zgyro: 0.0_f32,
19439 xmag: 0.0_f32,
19440 ymag: 0.0_f32,
19441 zmag: 0.0_f32,
19442 abs_pressure: 0.0_f32,
19443 diff_pressure: 0.0_f32,
19444 pressure_alt: 0.0_f32,
19445 temperature: 0.0_f32,
19446 fields_updated: HilSensorUpdatedFlags::DEFAULT,
19447 id: 0_u8,
19448 };
19449 #[cfg(feature = "arbitrary")]
19450 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19451 use arbitrary::{Arbitrary, Unstructured};
19452 let mut buf = [0u8; 1024];
19453 rng.fill_bytes(&mut buf);
19454 let mut unstructured = Unstructured::new(&buf);
19455 Self::arbitrary(&mut unstructured).unwrap_or_default()
19456 }
19457}
19458impl Default for HIL_SENSOR_DATA {
19459 fn default() -> Self {
19460 Self::DEFAULT.clone()
19461 }
19462}
19463impl MessageData for HIL_SENSOR_DATA {
19464 type Message = MavMessage;
19465 const ID: u32 = 107u32;
19466 const NAME: &'static str = "HIL_SENSOR";
19467 const EXTRA_CRC: u8 = 108u8;
19468 const ENCODED_LEN: usize = 65usize;
19469 fn deser(
19470 _version: MavlinkVersion,
19471 __input: &[u8],
19472 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19473 let avail_len = __input.len();
19474 let mut payload_buf = [0; Self::ENCODED_LEN];
19475 let mut buf = if avail_len < Self::ENCODED_LEN {
19476 payload_buf[0..avail_len].copy_from_slice(__input);
19477 Bytes::new(&payload_buf)
19478 } else {
19479 Bytes::new(__input)
19480 };
19481 let mut __struct = Self::default();
19482 __struct.time_usec = buf.get_u64_le();
19483 __struct.xacc = buf.get_f32_le();
19484 __struct.yacc = buf.get_f32_le();
19485 __struct.zacc = buf.get_f32_le();
19486 __struct.xgyro = buf.get_f32_le();
19487 __struct.ygyro = buf.get_f32_le();
19488 __struct.zgyro = buf.get_f32_le();
19489 __struct.xmag = buf.get_f32_le();
19490 __struct.ymag = buf.get_f32_le();
19491 __struct.zmag = buf.get_f32_le();
19492 __struct.abs_pressure = buf.get_f32_le();
19493 __struct.diff_pressure = buf.get_f32_le();
19494 __struct.pressure_alt = buf.get_f32_le();
19495 __struct.temperature = buf.get_f32_le();
19496 let tmp = buf.get_u32_le();
19497 __struct.fields_updated = HilSensorUpdatedFlags::from_bits(
19498 tmp & HilSensorUpdatedFlags::all().bits(),
19499 )
19500 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
19501 flag_type: "HilSensorUpdatedFlags",
19502 value: tmp as u32,
19503 })?;
19504 __struct.id = buf.get_u8();
19505 Ok(__struct)
19506 }
19507 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19508 let mut __tmp = BytesMut::new(bytes);
19509 #[allow(clippy::absurd_extreme_comparisons)]
19510 #[allow(unused_comparisons)]
19511 if __tmp.remaining() < Self::ENCODED_LEN {
19512 panic!(
19513 "buffer is too small (need {} bytes, but got {})",
19514 Self::ENCODED_LEN,
19515 __tmp.remaining(),
19516 )
19517 }
19518 __tmp.put_u64_le(self.time_usec);
19519 __tmp.put_f32_le(self.xacc);
19520 __tmp.put_f32_le(self.yacc);
19521 __tmp.put_f32_le(self.zacc);
19522 __tmp.put_f32_le(self.xgyro);
19523 __tmp.put_f32_le(self.ygyro);
19524 __tmp.put_f32_le(self.zgyro);
19525 __tmp.put_f32_le(self.xmag);
19526 __tmp.put_f32_le(self.ymag);
19527 __tmp.put_f32_le(self.zmag);
19528 __tmp.put_f32_le(self.abs_pressure);
19529 __tmp.put_f32_le(self.diff_pressure);
19530 __tmp.put_f32_le(self.pressure_alt);
19531 __tmp.put_f32_le(self.temperature);
19532 __tmp.put_u32_le(self.fields_updated.bits());
19533 __tmp.put_u8(self.id);
19534 if matches!(version, MavlinkVersion::V2) {
19535 let len = __tmp.len();
19536 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19537 } else {
19538 __tmp.len()
19539 }
19540 }
19541}
19542#[doc = "id: 142"]
19543#[doc = "The autopilot is requesting a resource (file, binary, other type of data)."]
19544#[derive(Debug, Clone, PartialEq)]
19545#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19546#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19547pub struct RESOURCE_REQUEST_DATA {
19548 #[doc = "Request ID. This ID should be re-used when sending back URI contents"]
19549 pub request_id: u8,
19550 #[doc = "The type of requested URI. 0 = a file via URL. 1 = a UAVCAN binary"]
19551 pub uri_type: u8,
19552 #[doc = "The requested unique resource identifier (URI). It is not necessarily a straight domain name (depends on the URI type enum)"]
19553 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19554 pub uri: [u8; 120],
19555 #[doc = "The way the autopilot wants to receive the URI. 0 = MAVLink FTP. 1 = binary stream."]
19556 pub transfer_type: u8,
19557 #[doc = "The storage path the autopilot wants the URI to be stored in. Will only be valid if the transfer_type has a storage associated (e.g. MAVLink FTP)."]
19558 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19559 pub storage: [u8; 120],
19560}
19561impl RESOURCE_REQUEST_DATA {
19562 pub const ENCODED_LEN: usize = 243usize;
19563 pub const DEFAULT: Self = Self {
19564 request_id: 0_u8,
19565 uri_type: 0_u8,
19566 uri: [0_u8; 120usize],
19567 transfer_type: 0_u8,
19568 storage: [0_u8; 120usize],
19569 };
19570 #[cfg(feature = "arbitrary")]
19571 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19572 use arbitrary::{Arbitrary, Unstructured};
19573 let mut buf = [0u8; 1024];
19574 rng.fill_bytes(&mut buf);
19575 let mut unstructured = Unstructured::new(&buf);
19576 Self::arbitrary(&mut unstructured).unwrap_or_default()
19577 }
19578}
19579impl Default for RESOURCE_REQUEST_DATA {
19580 fn default() -> Self {
19581 Self::DEFAULT.clone()
19582 }
19583}
19584impl MessageData for RESOURCE_REQUEST_DATA {
19585 type Message = MavMessage;
19586 const ID: u32 = 142u32;
19587 const NAME: &'static str = "RESOURCE_REQUEST";
19588 const EXTRA_CRC: u8 = 72u8;
19589 const ENCODED_LEN: usize = 243usize;
19590 fn deser(
19591 _version: MavlinkVersion,
19592 __input: &[u8],
19593 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19594 let avail_len = __input.len();
19595 let mut payload_buf = [0; Self::ENCODED_LEN];
19596 let mut buf = if avail_len < Self::ENCODED_LEN {
19597 payload_buf[0..avail_len].copy_from_slice(__input);
19598 Bytes::new(&payload_buf)
19599 } else {
19600 Bytes::new(__input)
19601 };
19602 let mut __struct = Self::default();
19603 __struct.request_id = buf.get_u8();
19604 __struct.uri_type = buf.get_u8();
19605 for v in &mut __struct.uri {
19606 let val = buf.get_u8();
19607 *v = val;
19608 }
19609 __struct.transfer_type = buf.get_u8();
19610 for v in &mut __struct.storage {
19611 let val = buf.get_u8();
19612 *v = val;
19613 }
19614 Ok(__struct)
19615 }
19616 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19617 let mut __tmp = BytesMut::new(bytes);
19618 #[allow(clippy::absurd_extreme_comparisons)]
19619 #[allow(unused_comparisons)]
19620 if __tmp.remaining() < Self::ENCODED_LEN {
19621 panic!(
19622 "buffer is too small (need {} bytes, but got {})",
19623 Self::ENCODED_LEN,
19624 __tmp.remaining(),
19625 )
19626 }
19627 __tmp.put_u8(self.request_id);
19628 __tmp.put_u8(self.uri_type);
19629 for val in &self.uri {
19630 __tmp.put_u8(*val);
19631 }
19632 __tmp.put_u8(self.transfer_type);
19633 for val in &self.storage {
19634 __tmp.put_u8(*val);
19635 }
19636 if matches!(version, MavlinkVersion::V2) {
19637 let len = __tmp.len();
19638 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19639 } else {
19640 __tmp.len()
19641 }
19642 }
19643}
19644#[doc = "id: 277"]
19645#[doc = "Camera absolute thermal range. This can be streamed when the associated VIDEO_STREAM_STATUS `flag` field bit VIDEO_STREAM_STATUS_FLAGS_THERMAL_RANGE_ENABLED is set, but a GCS may choose to only request it for the current active stream. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval (param3 indicates the stream id of the current camera, or 0 for all streams, param4 indicates the target camera_device_id for autopilot-attached cameras or 0 for MAVLink cameras)."]
19646#[derive(Debug, Clone, PartialEq)]
19647#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19648#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19649pub struct CAMERA_THERMAL_RANGE_DATA {
19650 #[doc = "Timestamp (time since system boot)."]
19651 pub time_boot_ms: u32,
19652 #[doc = "Temperature max."]
19653 pub max: f32,
19654 #[doc = "Temperature max point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
19655 pub max_point_x: f32,
19656 #[doc = "Temperature max point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
19657 pub max_point_y: f32,
19658 #[doc = "Temperature min."]
19659 pub min: f32,
19660 #[doc = "Temperature min point x value (normalized 0..1, 0 is left, 1 is right), NAN if unknown."]
19661 pub min_point_x: f32,
19662 #[doc = "Temperature min point y value (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown."]
19663 pub min_point_y: f32,
19664 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
19665 pub stream_id: u8,
19666 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
19667 pub camera_device_id: u8,
19668}
19669impl CAMERA_THERMAL_RANGE_DATA {
19670 pub const ENCODED_LEN: usize = 30usize;
19671 pub const DEFAULT: Self = Self {
19672 time_boot_ms: 0_u32,
19673 max: 0.0_f32,
19674 max_point_x: 0.0_f32,
19675 max_point_y: 0.0_f32,
19676 min: 0.0_f32,
19677 min_point_x: 0.0_f32,
19678 min_point_y: 0.0_f32,
19679 stream_id: 0_u8,
19680 camera_device_id: 0_u8,
19681 };
19682 #[cfg(feature = "arbitrary")]
19683 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19684 use arbitrary::{Arbitrary, Unstructured};
19685 let mut buf = [0u8; 1024];
19686 rng.fill_bytes(&mut buf);
19687 let mut unstructured = Unstructured::new(&buf);
19688 Self::arbitrary(&mut unstructured).unwrap_or_default()
19689 }
19690}
19691impl Default for CAMERA_THERMAL_RANGE_DATA {
19692 fn default() -> Self {
19693 Self::DEFAULT.clone()
19694 }
19695}
19696impl MessageData for CAMERA_THERMAL_RANGE_DATA {
19697 type Message = MavMessage;
19698 const ID: u32 = 277u32;
19699 const NAME: &'static str = "CAMERA_THERMAL_RANGE";
19700 const EXTRA_CRC: u8 = 62u8;
19701 const ENCODED_LEN: usize = 30usize;
19702 fn deser(
19703 _version: MavlinkVersion,
19704 __input: &[u8],
19705 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19706 let avail_len = __input.len();
19707 let mut payload_buf = [0; Self::ENCODED_LEN];
19708 let mut buf = if avail_len < Self::ENCODED_LEN {
19709 payload_buf[0..avail_len].copy_from_slice(__input);
19710 Bytes::new(&payload_buf)
19711 } else {
19712 Bytes::new(__input)
19713 };
19714 let mut __struct = Self::default();
19715 __struct.time_boot_ms = buf.get_u32_le();
19716 __struct.max = buf.get_f32_le();
19717 __struct.max_point_x = buf.get_f32_le();
19718 __struct.max_point_y = buf.get_f32_le();
19719 __struct.min = buf.get_f32_le();
19720 __struct.min_point_x = buf.get_f32_le();
19721 __struct.min_point_y = buf.get_f32_le();
19722 __struct.stream_id = buf.get_u8();
19723 __struct.camera_device_id = buf.get_u8();
19724 Ok(__struct)
19725 }
19726 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19727 let mut __tmp = BytesMut::new(bytes);
19728 #[allow(clippy::absurd_extreme_comparisons)]
19729 #[allow(unused_comparisons)]
19730 if __tmp.remaining() < Self::ENCODED_LEN {
19731 panic!(
19732 "buffer is too small (need {} bytes, but got {})",
19733 Self::ENCODED_LEN,
19734 __tmp.remaining(),
19735 )
19736 }
19737 __tmp.put_u32_le(self.time_boot_ms);
19738 __tmp.put_f32_le(self.max);
19739 __tmp.put_f32_le(self.max_point_x);
19740 __tmp.put_f32_le(self.max_point_y);
19741 __tmp.put_f32_le(self.min);
19742 __tmp.put_f32_le(self.min_point_x);
19743 __tmp.put_f32_le(self.min_point_y);
19744 __tmp.put_u8(self.stream_id);
19745 __tmp.put_u8(self.camera_device_id);
19746 if matches!(version, MavlinkVersion::V2) {
19747 let len = __tmp.len();
19748 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19749 } else {
19750 __tmp.len()
19751 }
19752 }
19753}
19754#[doc = "id: 111"]
19755#[doc = "Time synchronization message. The message is used for both timesync requests and responses. The request is sent with `ts1=syncing component timestamp` and `tc1=0`, and may be broadcast or targeted to a specific system/component. The response is sent with `ts1=syncing component timestamp` (mirror back unchanged), and `tc1=responding component timestamp`, with the `target_system` and `target_component` set to ids of the original request. Systems can determine if they are receiving a request or response based on the value of `tc`. If the response has `target_system==target_component==0` the remote system has not been updated to use the component IDs and cannot reliably timesync; the requestor may report an error. Timestamps are UNIX Epoch time or time since system boot in nanoseconds (the timestamp format can be inferred by checking for the magnitude of the number; generally it doesn't matter as only the offset is used). The message sequence is repeated numerous times with results being filtered/averaged to estimate the offset. See also: <https://mavlink.io/en/services/timesync.html>."]
19756#[derive(Debug, Clone, PartialEq)]
19757#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19758#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19759pub struct TIMESYNC_DATA {
19760 #[doc = "Time sync timestamp 1. Syncing: 0. Responding: Timestamp of responding component."]
19761 pub tc1: i64,
19762 #[doc = "Time sync timestamp 2. Timestamp of syncing component (mirrored in response)."]
19763 pub ts1: i64,
19764 #[doc = "Target system id. Request: 0 (broadcast) or id of specific system. Response must contain system id of the requesting component."]
19765 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19766 pub target_system: u8,
19767 #[doc = "Target component id. Request: 0 (broadcast) or id of specific component. Response must contain component id of the requesting component."]
19768 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
19769 pub target_component: u8,
19770}
19771impl TIMESYNC_DATA {
19772 pub const ENCODED_LEN: usize = 18usize;
19773 pub const DEFAULT: Self = Self {
19774 tc1: 0_i64,
19775 ts1: 0_i64,
19776 target_system: 0_u8,
19777 target_component: 0_u8,
19778 };
19779 #[cfg(feature = "arbitrary")]
19780 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19781 use arbitrary::{Arbitrary, Unstructured};
19782 let mut buf = [0u8; 1024];
19783 rng.fill_bytes(&mut buf);
19784 let mut unstructured = Unstructured::new(&buf);
19785 Self::arbitrary(&mut unstructured).unwrap_or_default()
19786 }
19787}
19788impl Default for TIMESYNC_DATA {
19789 fn default() -> Self {
19790 Self::DEFAULT.clone()
19791 }
19792}
19793impl MessageData for TIMESYNC_DATA {
19794 type Message = MavMessage;
19795 const ID: u32 = 111u32;
19796 const NAME: &'static str = "TIMESYNC";
19797 const EXTRA_CRC: u8 = 34u8;
19798 const ENCODED_LEN: usize = 18usize;
19799 fn deser(
19800 _version: MavlinkVersion,
19801 __input: &[u8],
19802 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19803 let avail_len = __input.len();
19804 let mut payload_buf = [0; Self::ENCODED_LEN];
19805 let mut buf = if avail_len < Self::ENCODED_LEN {
19806 payload_buf[0..avail_len].copy_from_slice(__input);
19807 Bytes::new(&payload_buf)
19808 } else {
19809 Bytes::new(__input)
19810 };
19811 let mut __struct = Self::default();
19812 __struct.tc1 = buf.get_i64_le();
19813 __struct.ts1 = buf.get_i64_le();
19814 __struct.target_system = buf.get_u8();
19815 __struct.target_component = buf.get_u8();
19816 Ok(__struct)
19817 }
19818 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19819 let mut __tmp = BytesMut::new(bytes);
19820 #[allow(clippy::absurd_extreme_comparisons)]
19821 #[allow(unused_comparisons)]
19822 if __tmp.remaining() < Self::ENCODED_LEN {
19823 panic!(
19824 "buffer is too small (need {} bytes, but got {})",
19825 Self::ENCODED_LEN,
19826 __tmp.remaining(),
19827 )
19828 }
19829 __tmp.put_i64_le(self.tc1);
19830 __tmp.put_i64_le(self.ts1);
19831 __tmp.put_u8(self.target_system);
19832 __tmp.put_u8(self.target_component);
19833 if matches!(version, MavlinkVersion::V2) {
19834 let len = __tmp.len();
19835 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19836 } else {
19837 __tmp.len()
19838 }
19839 }
19840}
19841#[doc = "id: 12915"]
19842#[doc = "An OpenDroneID message pack is a container for multiple encoded OpenDroneID messages (i.e. not in the format given for the above message descriptions but after encoding into the compressed OpenDroneID byte format). Used e.g. when transmitting on Bluetooth 5.0 Long Range/Extended Advertising or on WiFi Neighbor Aware Networking or on WiFi Beacon."]
19843#[derive(Debug, Clone, PartialEq)]
19844#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19845#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19846pub struct OPEN_DRONE_ID_MESSAGE_PACK_DATA {
19847 #[doc = "System ID (0 for broadcast)."]
19848 pub target_system: u8,
19849 #[doc = "Component ID (0 for broadcast)."]
19850 pub target_component: u8,
19851 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
19852 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19853 pub id_or_mac: [u8; 20],
19854 #[doc = "This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specified to have this length."]
19855 pub single_message_size: u8,
19856 #[doc = "Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 9."]
19857 pub msg_pack_size: u8,
19858 #[doc = "Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field."]
19859 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
19860 pub messages: [u8; 225],
19861}
19862impl OPEN_DRONE_ID_MESSAGE_PACK_DATA {
19863 pub const ENCODED_LEN: usize = 249usize;
19864 pub const DEFAULT: Self = Self {
19865 target_system: 0_u8,
19866 target_component: 0_u8,
19867 id_or_mac: [0_u8; 20usize],
19868 single_message_size: 0_u8,
19869 msg_pack_size: 0_u8,
19870 messages: [0_u8; 225usize],
19871 };
19872 #[cfg(feature = "arbitrary")]
19873 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19874 use arbitrary::{Arbitrary, Unstructured};
19875 let mut buf = [0u8; 1024];
19876 rng.fill_bytes(&mut buf);
19877 let mut unstructured = Unstructured::new(&buf);
19878 Self::arbitrary(&mut unstructured).unwrap_or_default()
19879 }
19880}
19881impl Default for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
19882 fn default() -> Self {
19883 Self::DEFAULT.clone()
19884 }
19885}
19886impl MessageData for OPEN_DRONE_ID_MESSAGE_PACK_DATA {
19887 type Message = MavMessage;
19888 const ID: u32 = 12915u32;
19889 const NAME: &'static str = "OPEN_DRONE_ID_MESSAGE_PACK";
19890 const EXTRA_CRC: u8 = 94u8;
19891 const ENCODED_LEN: usize = 249usize;
19892 fn deser(
19893 _version: MavlinkVersion,
19894 __input: &[u8],
19895 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19896 let avail_len = __input.len();
19897 let mut payload_buf = [0; Self::ENCODED_LEN];
19898 let mut buf = if avail_len < Self::ENCODED_LEN {
19899 payload_buf[0..avail_len].copy_from_slice(__input);
19900 Bytes::new(&payload_buf)
19901 } else {
19902 Bytes::new(__input)
19903 };
19904 let mut __struct = Self::default();
19905 __struct.target_system = buf.get_u8();
19906 __struct.target_component = buf.get_u8();
19907 for v in &mut __struct.id_or_mac {
19908 let val = buf.get_u8();
19909 *v = val;
19910 }
19911 __struct.single_message_size = buf.get_u8();
19912 __struct.msg_pack_size = buf.get_u8();
19913 for v in &mut __struct.messages {
19914 let val = buf.get_u8();
19915 *v = val;
19916 }
19917 Ok(__struct)
19918 }
19919 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
19920 let mut __tmp = BytesMut::new(bytes);
19921 #[allow(clippy::absurd_extreme_comparisons)]
19922 #[allow(unused_comparisons)]
19923 if __tmp.remaining() < Self::ENCODED_LEN {
19924 panic!(
19925 "buffer is too small (need {} bytes, but got {})",
19926 Self::ENCODED_LEN,
19927 __tmp.remaining(),
19928 )
19929 }
19930 __tmp.put_u8(self.target_system);
19931 __tmp.put_u8(self.target_component);
19932 for val in &self.id_or_mac {
19933 __tmp.put_u8(*val);
19934 }
19935 __tmp.put_u8(self.single_message_size);
19936 __tmp.put_u8(self.msg_pack_size);
19937 for val in &self.messages {
19938 __tmp.put_u8(*val);
19939 }
19940 if matches!(version, MavlinkVersion::V2) {
19941 let len = __tmp.len();
19942 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
19943 } else {
19944 __tmp.len()
19945 }
19946 }
19947}
19948#[doc = "id: 119"]
19949#[doc = "Request a chunk of a log."]
19950#[derive(Debug, Clone, PartialEq)]
19951#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
19952#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
19953pub struct LOG_REQUEST_DATA_DATA {
19954 #[doc = "Offset into the log"]
19955 pub ofs: u32,
19956 #[doc = "Number of bytes"]
19957 pub count: u32,
19958 #[doc = "Log id (from LOG_ENTRY reply)"]
19959 pub id: u16,
19960 #[doc = "System ID"]
19961 pub target_system: u8,
19962 #[doc = "Component ID"]
19963 pub target_component: u8,
19964}
19965impl LOG_REQUEST_DATA_DATA {
19966 pub const ENCODED_LEN: usize = 12usize;
19967 pub const DEFAULT: Self = Self {
19968 ofs: 0_u32,
19969 count: 0_u32,
19970 id: 0_u16,
19971 target_system: 0_u8,
19972 target_component: 0_u8,
19973 };
19974 #[cfg(feature = "arbitrary")]
19975 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
19976 use arbitrary::{Arbitrary, Unstructured};
19977 let mut buf = [0u8; 1024];
19978 rng.fill_bytes(&mut buf);
19979 let mut unstructured = Unstructured::new(&buf);
19980 Self::arbitrary(&mut unstructured).unwrap_or_default()
19981 }
19982}
19983impl Default for LOG_REQUEST_DATA_DATA {
19984 fn default() -> Self {
19985 Self::DEFAULT.clone()
19986 }
19987}
19988impl MessageData for LOG_REQUEST_DATA_DATA {
19989 type Message = MavMessage;
19990 const ID: u32 = 119u32;
19991 const NAME: &'static str = "LOG_REQUEST_DATA";
19992 const EXTRA_CRC: u8 = 116u8;
19993 const ENCODED_LEN: usize = 12usize;
19994 fn deser(
19995 _version: MavlinkVersion,
19996 __input: &[u8],
19997 ) -> Result<Self, ::mavlink_core::error::ParserError> {
19998 let avail_len = __input.len();
19999 let mut payload_buf = [0; Self::ENCODED_LEN];
20000 let mut buf = if avail_len < Self::ENCODED_LEN {
20001 payload_buf[0..avail_len].copy_from_slice(__input);
20002 Bytes::new(&payload_buf)
20003 } else {
20004 Bytes::new(__input)
20005 };
20006 let mut __struct = Self::default();
20007 __struct.ofs = buf.get_u32_le();
20008 __struct.count = buf.get_u32_le();
20009 __struct.id = buf.get_u16_le();
20010 __struct.target_system = buf.get_u8();
20011 __struct.target_component = buf.get_u8();
20012 Ok(__struct)
20013 }
20014 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20015 let mut __tmp = BytesMut::new(bytes);
20016 #[allow(clippy::absurd_extreme_comparisons)]
20017 #[allow(unused_comparisons)]
20018 if __tmp.remaining() < Self::ENCODED_LEN {
20019 panic!(
20020 "buffer is too small (need {} bytes, but got {})",
20021 Self::ENCODED_LEN,
20022 __tmp.remaining(),
20023 )
20024 }
20025 __tmp.put_u32_le(self.ofs);
20026 __tmp.put_u32_le(self.count);
20027 __tmp.put_u16_le(self.id);
20028 __tmp.put_u8(self.target_system);
20029 __tmp.put_u8(self.target_component);
20030 if matches!(version, MavlinkVersion::V2) {
20031 let len = __tmp.len();
20032 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20033 } else {
20034 __tmp.len()
20035 }
20036 }
20037}
20038#[doc = "id: 397"]
20039#[doc = "Component metadata message, which may be requested using MAV_CMD_REQUEST_MESSAGE. This contains the MAVLink FTP URI and CRC for the component's general metadata file. The file must be hosted on the component, and may be xz compressed. The file CRC can be used for file caching. The general metadata file can be read to get the locations of other metadata files (COMP_METADATA_TYPE) and translations, which may be hosted either on the vehicle or the internet. For more information see: <https://mavlink.io/en/services/component_information.html>. Note: Camera components should use CAMERA_INFORMATION instead, and autopilots may use both this message and AUTOPILOT_VERSION."]
20040#[derive(Debug, Clone, PartialEq)]
20041#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20042#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20043pub struct COMPONENT_METADATA_DATA {
20044 #[doc = "Timestamp (time since system boot)."]
20045 pub time_boot_ms: u32,
20046 #[doc = "CRC32 of the general metadata file."]
20047 pub file_crc: u32,
20048 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
20049 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20050 pub uri: [u8; 100],
20051}
20052impl COMPONENT_METADATA_DATA {
20053 pub const ENCODED_LEN: usize = 108usize;
20054 pub const DEFAULT: Self = Self {
20055 time_boot_ms: 0_u32,
20056 file_crc: 0_u32,
20057 uri: [0_u8; 100usize],
20058 };
20059 #[cfg(feature = "arbitrary")]
20060 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20061 use arbitrary::{Arbitrary, Unstructured};
20062 let mut buf = [0u8; 1024];
20063 rng.fill_bytes(&mut buf);
20064 let mut unstructured = Unstructured::new(&buf);
20065 Self::arbitrary(&mut unstructured).unwrap_or_default()
20066 }
20067}
20068impl Default for COMPONENT_METADATA_DATA {
20069 fn default() -> Self {
20070 Self::DEFAULT.clone()
20071 }
20072}
20073impl MessageData for COMPONENT_METADATA_DATA {
20074 type Message = MavMessage;
20075 const ID: u32 = 397u32;
20076 const NAME: &'static str = "COMPONENT_METADATA";
20077 const EXTRA_CRC: u8 = 182u8;
20078 const ENCODED_LEN: usize = 108usize;
20079 fn deser(
20080 _version: MavlinkVersion,
20081 __input: &[u8],
20082 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20083 let avail_len = __input.len();
20084 let mut payload_buf = [0; Self::ENCODED_LEN];
20085 let mut buf = if avail_len < Self::ENCODED_LEN {
20086 payload_buf[0..avail_len].copy_from_slice(__input);
20087 Bytes::new(&payload_buf)
20088 } else {
20089 Bytes::new(__input)
20090 };
20091 let mut __struct = Self::default();
20092 __struct.time_boot_ms = buf.get_u32_le();
20093 __struct.file_crc = buf.get_u32_le();
20094 for v in &mut __struct.uri {
20095 let val = buf.get_u8();
20096 *v = val;
20097 }
20098 Ok(__struct)
20099 }
20100 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20101 let mut __tmp = BytesMut::new(bytes);
20102 #[allow(clippy::absurd_extreme_comparisons)]
20103 #[allow(unused_comparisons)]
20104 if __tmp.remaining() < Self::ENCODED_LEN {
20105 panic!(
20106 "buffer is too small (need {} bytes, but got {})",
20107 Self::ENCODED_LEN,
20108 __tmp.remaining(),
20109 )
20110 }
20111 __tmp.put_u32_le(self.time_boot_ms);
20112 __tmp.put_u32_le(self.file_crc);
20113 for val in &self.uri {
20114 __tmp.put_u8(*val);
20115 }
20116 if matches!(version, MavlinkVersion::V2) {
20117 let len = __tmp.len();
20118 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20119 } else {
20120 __tmp.len()
20121 }
20122 }
20123}
20124#[doc = "id: 192"]
20125#[doc = "Reports results of completed compass calibration. Sent until MAG_CAL_ACK received."]
20126#[derive(Debug, Clone, PartialEq)]
20127#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20128#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20129pub struct MAG_CAL_REPORT_DATA {
20130 #[doc = "RMS milligauss residuals."]
20131 pub fitness: f32,
20132 #[doc = "X offset."]
20133 pub ofs_x: f32,
20134 #[doc = "Y offset."]
20135 pub ofs_y: f32,
20136 #[doc = "Z offset."]
20137 pub ofs_z: f32,
20138 #[doc = "X diagonal (matrix 11)."]
20139 pub diag_x: f32,
20140 #[doc = "Y diagonal (matrix 22)."]
20141 pub diag_y: f32,
20142 #[doc = "Z diagonal (matrix 33)."]
20143 pub diag_z: f32,
20144 #[doc = "X off-diagonal (matrix 12 and 21)."]
20145 pub offdiag_x: f32,
20146 #[doc = "Y off-diagonal (matrix 13 and 31)."]
20147 pub offdiag_y: f32,
20148 #[doc = "Z off-diagonal (matrix 32 and 23)."]
20149 pub offdiag_z: f32,
20150 #[doc = "Compass being calibrated."]
20151 pub compass_id: u8,
20152 #[doc = "Bitmask of compasses being calibrated."]
20153 pub cal_mask: u8,
20154 #[doc = "Calibration Status."]
20155 pub cal_status: MagCalStatus,
20156 #[doc = "0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters."]
20157 pub autosaved: u8,
20158 #[doc = "Confidence in orientation (higher is better)."]
20159 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20160 pub orientation_confidence: f32,
20161 #[doc = "orientation before calibration."]
20162 #[cfg_attr(feature = "serde", serde(default))]
20163 pub old_orientation: MavSensorOrientation,
20164 #[doc = "orientation after calibration."]
20165 #[cfg_attr(feature = "serde", serde(default))]
20166 pub new_orientation: MavSensorOrientation,
20167 #[doc = "field radius correction factor"]
20168 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20169 pub scale_factor: f32,
20170}
20171impl MAG_CAL_REPORT_DATA {
20172 pub const ENCODED_LEN: usize = 54usize;
20173 pub const DEFAULT: Self = Self {
20174 fitness: 0.0_f32,
20175 ofs_x: 0.0_f32,
20176 ofs_y: 0.0_f32,
20177 ofs_z: 0.0_f32,
20178 diag_x: 0.0_f32,
20179 diag_y: 0.0_f32,
20180 diag_z: 0.0_f32,
20181 offdiag_x: 0.0_f32,
20182 offdiag_y: 0.0_f32,
20183 offdiag_z: 0.0_f32,
20184 compass_id: 0_u8,
20185 cal_mask: 0_u8,
20186 cal_status: MagCalStatus::DEFAULT,
20187 autosaved: 0_u8,
20188 orientation_confidence: 0.0_f32,
20189 old_orientation: MavSensorOrientation::DEFAULT,
20190 new_orientation: MavSensorOrientation::DEFAULT,
20191 scale_factor: 0.0_f32,
20192 };
20193 #[cfg(feature = "arbitrary")]
20194 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20195 use arbitrary::{Arbitrary, Unstructured};
20196 let mut buf = [0u8; 1024];
20197 rng.fill_bytes(&mut buf);
20198 let mut unstructured = Unstructured::new(&buf);
20199 Self::arbitrary(&mut unstructured).unwrap_or_default()
20200 }
20201}
20202impl Default for MAG_CAL_REPORT_DATA {
20203 fn default() -> Self {
20204 Self::DEFAULT.clone()
20205 }
20206}
20207impl MessageData for MAG_CAL_REPORT_DATA {
20208 type Message = MavMessage;
20209 const ID: u32 = 192u32;
20210 const NAME: &'static str = "MAG_CAL_REPORT";
20211 const EXTRA_CRC: u8 = 36u8;
20212 const ENCODED_LEN: usize = 54usize;
20213 fn deser(
20214 _version: MavlinkVersion,
20215 __input: &[u8],
20216 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20217 let avail_len = __input.len();
20218 let mut payload_buf = [0; Self::ENCODED_LEN];
20219 let mut buf = if avail_len < Self::ENCODED_LEN {
20220 payload_buf[0..avail_len].copy_from_slice(__input);
20221 Bytes::new(&payload_buf)
20222 } else {
20223 Bytes::new(__input)
20224 };
20225 let mut __struct = Self::default();
20226 __struct.fitness = buf.get_f32_le();
20227 __struct.ofs_x = buf.get_f32_le();
20228 __struct.ofs_y = buf.get_f32_le();
20229 __struct.ofs_z = buf.get_f32_le();
20230 __struct.diag_x = buf.get_f32_le();
20231 __struct.diag_y = buf.get_f32_le();
20232 __struct.diag_z = buf.get_f32_le();
20233 __struct.offdiag_x = buf.get_f32_le();
20234 __struct.offdiag_y = buf.get_f32_le();
20235 __struct.offdiag_z = buf.get_f32_le();
20236 __struct.compass_id = buf.get_u8();
20237 __struct.cal_mask = buf.get_u8();
20238 let tmp = buf.get_u8();
20239 __struct.cal_status =
20240 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20241 enum_type: "MagCalStatus",
20242 value: tmp as u32,
20243 })?;
20244 __struct.autosaved = buf.get_u8();
20245 __struct.orientation_confidence = buf.get_f32_le();
20246 let tmp = buf.get_u8();
20247 __struct.old_orientation =
20248 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20249 enum_type: "MavSensorOrientation",
20250 value: tmp as u32,
20251 })?;
20252 let tmp = buf.get_u8();
20253 __struct.new_orientation =
20254 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20255 enum_type: "MavSensorOrientation",
20256 value: tmp as u32,
20257 })?;
20258 __struct.scale_factor = buf.get_f32_le();
20259 Ok(__struct)
20260 }
20261 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20262 let mut __tmp = BytesMut::new(bytes);
20263 #[allow(clippy::absurd_extreme_comparisons)]
20264 #[allow(unused_comparisons)]
20265 if __tmp.remaining() < Self::ENCODED_LEN {
20266 panic!(
20267 "buffer is too small (need {} bytes, but got {})",
20268 Self::ENCODED_LEN,
20269 __tmp.remaining(),
20270 )
20271 }
20272 __tmp.put_f32_le(self.fitness);
20273 __tmp.put_f32_le(self.ofs_x);
20274 __tmp.put_f32_le(self.ofs_y);
20275 __tmp.put_f32_le(self.ofs_z);
20276 __tmp.put_f32_le(self.diag_x);
20277 __tmp.put_f32_le(self.diag_y);
20278 __tmp.put_f32_le(self.diag_z);
20279 __tmp.put_f32_le(self.offdiag_x);
20280 __tmp.put_f32_le(self.offdiag_y);
20281 __tmp.put_f32_le(self.offdiag_z);
20282 __tmp.put_u8(self.compass_id);
20283 __tmp.put_u8(self.cal_mask);
20284 __tmp.put_u8(self.cal_status as u8);
20285 __tmp.put_u8(self.autosaved);
20286 __tmp.put_f32_le(self.orientation_confidence);
20287 __tmp.put_u8(self.old_orientation as u8);
20288 __tmp.put_u8(self.new_orientation as u8);
20289 __tmp.put_f32_le(self.scale_factor);
20290 if matches!(version, MavlinkVersion::V2) {
20291 let len = __tmp.len();
20292 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20293 } else {
20294 __tmp.len()
20295 }
20296 }
20297}
20298#[doc = "id: 252"]
20299#[doc = "Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output."]
20300#[derive(Debug, Clone, PartialEq)]
20301#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20302#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20303pub struct NAMED_VALUE_INT_DATA {
20304 #[doc = "Timestamp (time since system boot)."]
20305 pub time_boot_ms: u32,
20306 #[doc = "Signed integer value"]
20307 pub value: i32,
20308 #[doc = "Name of the debug variable"]
20309 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20310 pub name: [u8; 10],
20311}
20312impl NAMED_VALUE_INT_DATA {
20313 pub const ENCODED_LEN: usize = 18usize;
20314 pub const DEFAULT: Self = Self {
20315 time_boot_ms: 0_u32,
20316 value: 0_i32,
20317 name: [0_u8; 10usize],
20318 };
20319 #[cfg(feature = "arbitrary")]
20320 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20321 use arbitrary::{Arbitrary, Unstructured};
20322 let mut buf = [0u8; 1024];
20323 rng.fill_bytes(&mut buf);
20324 let mut unstructured = Unstructured::new(&buf);
20325 Self::arbitrary(&mut unstructured).unwrap_or_default()
20326 }
20327}
20328impl Default for NAMED_VALUE_INT_DATA {
20329 fn default() -> Self {
20330 Self::DEFAULT.clone()
20331 }
20332}
20333impl MessageData for NAMED_VALUE_INT_DATA {
20334 type Message = MavMessage;
20335 const ID: u32 = 252u32;
20336 const NAME: &'static str = "NAMED_VALUE_INT";
20337 const EXTRA_CRC: u8 = 44u8;
20338 const ENCODED_LEN: usize = 18usize;
20339 fn deser(
20340 _version: MavlinkVersion,
20341 __input: &[u8],
20342 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20343 let avail_len = __input.len();
20344 let mut payload_buf = [0; Self::ENCODED_LEN];
20345 let mut buf = if avail_len < Self::ENCODED_LEN {
20346 payload_buf[0..avail_len].copy_from_slice(__input);
20347 Bytes::new(&payload_buf)
20348 } else {
20349 Bytes::new(__input)
20350 };
20351 let mut __struct = Self::default();
20352 __struct.time_boot_ms = buf.get_u32_le();
20353 __struct.value = buf.get_i32_le();
20354 for v in &mut __struct.name {
20355 let val = buf.get_u8();
20356 *v = val;
20357 }
20358 Ok(__struct)
20359 }
20360 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20361 let mut __tmp = BytesMut::new(bytes);
20362 #[allow(clippy::absurd_extreme_comparisons)]
20363 #[allow(unused_comparisons)]
20364 if __tmp.remaining() < Self::ENCODED_LEN {
20365 panic!(
20366 "buffer is too small (need {} bytes, but got {})",
20367 Self::ENCODED_LEN,
20368 __tmp.remaining(),
20369 )
20370 }
20371 __tmp.put_u32_le(self.time_boot_ms);
20372 __tmp.put_i32_le(self.value);
20373 for val in &self.name {
20374 __tmp.put_u8(*val);
20375 }
20376 if matches!(version, MavlinkVersion::V2) {
20377 let len = __tmp.len();
20378 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20379 } else {
20380 __tmp.len()
20381 }
20382 }
20383}
20384#[doc = "id: 55"]
20385#[doc = "Read out the safety zone the MAV currently assumes."]
20386#[derive(Debug, Clone, PartialEq)]
20387#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20388#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20389pub struct SAFETY_ALLOWED_AREA_DATA {
20390 #[doc = "x position 1 / Latitude 1"]
20391 pub p1x: f32,
20392 #[doc = "y position 1 / Longitude 1"]
20393 pub p1y: f32,
20394 #[doc = "z position 1 / Altitude 1"]
20395 pub p1z: f32,
20396 #[doc = "x position 2 / Latitude 2"]
20397 pub p2x: f32,
20398 #[doc = "y position 2 / Longitude 2"]
20399 pub p2y: f32,
20400 #[doc = "z position 2 / Altitude 2"]
20401 pub p2z: f32,
20402 #[doc = "Coordinate frame. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down."]
20403 pub frame: MavFrame,
20404}
20405impl SAFETY_ALLOWED_AREA_DATA {
20406 pub const ENCODED_LEN: usize = 25usize;
20407 pub const DEFAULT: Self = Self {
20408 p1x: 0.0_f32,
20409 p1y: 0.0_f32,
20410 p1z: 0.0_f32,
20411 p2x: 0.0_f32,
20412 p2y: 0.0_f32,
20413 p2z: 0.0_f32,
20414 frame: MavFrame::DEFAULT,
20415 };
20416 #[cfg(feature = "arbitrary")]
20417 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20418 use arbitrary::{Arbitrary, Unstructured};
20419 let mut buf = [0u8; 1024];
20420 rng.fill_bytes(&mut buf);
20421 let mut unstructured = Unstructured::new(&buf);
20422 Self::arbitrary(&mut unstructured).unwrap_or_default()
20423 }
20424}
20425impl Default for SAFETY_ALLOWED_AREA_DATA {
20426 fn default() -> Self {
20427 Self::DEFAULT.clone()
20428 }
20429}
20430impl MessageData for SAFETY_ALLOWED_AREA_DATA {
20431 type Message = MavMessage;
20432 const ID: u32 = 55u32;
20433 const NAME: &'static str = "SAFETY_ALLOWED_AREA";
20434 const EXTRA_CRC: u8 = 3u8;
20435 const ENCODED_LEN: usize = 25usize;
20436 fn deser(
20437 _version: MavlinkVersion,
20438 __input: &[u8],
20439 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20440 let avail_len = __input.len();
20441 let mut payload_buf = [0; Self::ENCODED_LEN];
20442 let mut buf = if avail_len < Self::ENCODED_LEN {
20443 payload_buf[0..avail_len].copy_from_slice(__input);
20444 Bytes::new(&payload_buf)
20445 } else {
20446 Bytes::new(__input)
20447 };
20448 let mut __struct = Self::default();
20449 __struct.p1x = buf.get_f32_le();
20450 __struct.p1y = buf.get_f32_le();
20451 __struct.p1z = buf.get_f32_le();
20452 __struct.p2x = buf.get_f32_le();
20453 __struct.p2y = buf.get_f32_le();
20454 __struct.p2z = buf.get_f32_le();
20455 let tmp = buf.get_u8();
20456 __struct.frame =
20457 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
20458 enum_type: "MavFrame",
20459 value: tmp as u32,
20460 })?;
20461 Ok(__struct)
20462 }
20463 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20464 let mut __tmp = BytesMut::new(bytes);
20465 #[allow(clippy::absurd_extreme_comparisons)]
20466 #[allow(unused_comparisons)]
20467 if __tmp.remaining() < Self::ENCODED_LEN {
20468 panic!(
20469 "buffer is too small (need {} bytes, but got {})",
20470 Self::ENCODED_LEN,
20471 __tmp.remaining(),
20472 )
20473 }
20474 __tmp.put_f32_le(self.p1x);
20475 __tmp.put_f32_le(self.p1y);
20476 __tmp.put_f32_le(self.p1z);
20477 __tmp.put_f32_le(self.p2x);
20478 __tmp.put_f32_le(self.p2y);
20479 __tmp.put_f32_le(self.p2z);
20480 __tmp.put_u8(self.frame as u8);
20481 if matches!(version, MavlinkVersion::V2) {
20482 let len = __tmp.len();
20483 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20484 } else {
20485 __tmp.len()
20486 }
20487 }
20488}
20489#[doc = "id: 285"]
20490#[doc = "Message reporting the status of a gimbal device. \t This message should be broadcast by a gimbal device component at a low regular rate (e.g. 5 Hz). \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Other conditions of the flags are not allowed. \t The quaternion and angular velocities in the other frame can be calculated from delta_yaw and delta_yaw_velocity as \t q_earth = q_delta_yaw * q_vehicle and w_earth = w_delta_yaw_velocity + w_vehicle (if not NaN). \t If neither the GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME nor the GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME flag is set, \t then (for backwards compatibility) the data in the delta_yaw and delta_yaw_velocity fields are to be ignored. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME, \t and always should set delta_yaw and delta_yaw_velocity either to the proper value or NaN."]
20491#[derive(Debug, Clone, PartialEq)]
20492#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20493#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20494pub struct GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
20495 #[doc = "Timestamp (time since system boot)."]
20496 pub time_boot_ms: u32,
20497 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description."]
20498 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20499 pub q: [f32; 4],
20500 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN if unknown."]
20501 pub angular_velocity_x: f32,
20502 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN if unknown."]
20503 pub angular_velocity_y: f32,
20504 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN if unknown."]
20505 pub angular_velocity_z: f32,
20506 #[doc = "Failure flags (0 for no failure)"]
20507 pub failure_flags: GimbalDeviceErrorFlags,
20508 #[doc = "Current gimbal flags set."]
20509 pub flags: GimbalDeviceFlags,
20510 #[doc = "System ID"]
20511 pub target_system: u8,
20512 #[doc = "Component ID"]
20513 pub target_component: u8,
20514 #[doc = "Yaw angle relating the quaternions in earth and body frames (see message description). NaN if unknown."]
20515 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20516 pub delta_yaw: f32,
20517 #[doc = "Yaw angular velocity relating the angular velocities in earth and body frames (see message description). NaN if unknown."]
20518 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20519 pub delta_yaw_velocity: f32,
20520 #[doc = "This field is to be used if the gimbal manager and the gimbal device are the same component and hence have the same component ID. This field is then set a number between 1-6. If the component ID is separate, this field is not required and must be set to 0."]
20521 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20522 pub gimbal_device_id: u8,
20523}
20524impl GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
20525 pub const ENCODED_LEN: usize = 49usize;
20526 pub const DEFAULT: Self = Self {
20527 time_boot_ms: 0_u32,
20528 q: [0.0_f32; 4usize],
20529 angular_velocity_x: 0.0_f32,
20530 angular_velocity_y: 0.0_f32,
20531 angular_velocity_z: 0.0_f32,
20532 failure_flags: GimbalDeviceErrorFlags::DEFAULT,
20533 flags: GimbalDeviceFlags::DEFAULT,
20534 target_system: 0_u8,
20535 target_component: 0_u8,
20536 delta_yaw: 0.0_f32,
20537 delta_yaw_velocity: 0.0_f32,
20538 gimbal_device_id: 0_u8,
20539 };
20540 #[cfg(feature = "arbitrary")]
20541 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20542 use arbitrary::{Arbitrary, Unstructured};
20543 let mut buf = [0u8; 1024];
20544 rng.fill_bytes(&mut buf);
20545 let mut unstructured = Unstructured::new(&buf);
20546 Self::arbitrary(&mut unstructured).unwrap_or_default()
20547 }
20548}
20549impl Default for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
20550 fn default() -> Self {
20551 Self::DEFAULT.clone()
20552 }
20553}
20554impl MessageData for GIMBAL_DEVICE_ATTITUDE_STATUS_DATA {
20555 type Message = MavMessage;
20556 const ID: u32 = 285u32;
20557 const NAME: &'static str = "GIMBAL_DEVICE_ATTITUDE_STATUS";
20558 const EXTRA_CRC: u8 = 137u8;
20559 const ENCODED_LEN: usize = 49usize;
20560 fn deser(
20561 _version: MavlinkVersion,
20562 __input: &[u8],
20563 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20564 let avail_len = __input.len();
20565 let mut payload_buf = [0; Self::ENCODED_LEN];
20566 let mut buf = if avail_len < Self::ENCODED_LEN {
20567 payload_buf[0..avail_len].copy_from_slice(__input);
20568 Bytes::new(&payload_buf)
20569 } else {
20570 Bytes::new(__input)
20571 };
20572 let mut __struct = Self::default();
20573 __struct.time_boot_ms = buf.get_u32_le();
20574 for v in &mut __struct.q {
20575 let val = buf.get_f32_le();
20576 *v = val;
20577 }
20578 __struct.angular_velocity_x = buf.get_f32_le();
20579 __struct.angular_velocity_y = buf.get_f32_le();
20580 __struct.angular_velocity_z = buf.get_f32_le();
20581 let tmp = buf.get_u32_le();
20582 __struct.failure_flags = GimbalDeviceErrorFlags::from_bits(
20583 tmp & GimbalDeviceErrorFlags::all().bits(),
20584 )
20585 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
20586 flag_type: "GimbalDeviceErrorFlags",
20587 value: tmp as u32,
20588 })?;
20589 let tmp = buf.get_u16_le();
20590 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
20591 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
20592 flag_type: "GimbalDeviceFlags",
20593 value: tmp as u32,
20594 })?;
20595 __struct.target_system = buf.get_u8();
20596 __struct.target_component = buf.get_u8();
20597 __struct.delta_yaw = buf.get_f32_le();
20598 __struct.delta_yaw_velocity = buf.get_f32_le();
20599 __struct.gimbal_device_id = buf.get_u8();
20600 Ok(__struct)
20601 }
20602 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20603 let mut __tmp = BytesMut::new(bytes);
20604 #[allow(clippy::absurd_extreme_comparisons)]
20605 #[allow(unused_comparisons)]
20606 if __tmp.remaining() < Self::ENCODED_LEN {
20607 panic!(
20608 "buffer is too small (need {} bytes, but got {})",
20609 Self::ENCODED_LEN,
20610 __tmp.remaining(),
20611 )
20612 }
20613 __tmp.put_u32_le(self.time_boot_ms);
20614 for val in &self.q {
20615 __tmp.put_f32_le(*val);
20616 }
20617 __tmp.put_f32_le(self.angular_velocity_x);
20618 __tmp.put_f32_le(self.angular_velocity_y);
20619 __tmp.put_f32_le(self.angular_velocity_z);
20620 __tmp.put_u32_le(self.failure_flags.bits());
20621 __tmp.put_u16_le(self.flags.bits());
20622 __tmp.put_u8(self.target_system);
20623 __tmp.put_u8(self.target_component);
20624 __tmp.put_f32_le(self.delta_yaw);
20625 __tmp.put_f32_le(self.delta_yaw_velocity);
20626 __tmp.put_u8(self.gimbal_device_id);
20627 if matches!(version, MavlinkVersion::V2) {
20628 let len = __tmp.len();
20629 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20630 } else {
20631 __tmp.len()
20632 }
20633 }
20634}
20635#[doc = "id: 291"]
20636#[doc = "ESC information for higher rate streaming. Recommended streaming rate is ~10 Hz. Information that changes more slowly is sent in ESC_INFO. It should typically only be streamed on high-bandwidth links (i.e. to a companion computer)."]
20637#[derive(Debug, Clone, PartialEq)]
20638#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20639#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20640pub struct ESC_STATUS_DATA {
20641 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number."]
20642 pub time_usec: u64,
20643 #[doc = "Reported motor RPM from each ESC (negative for reverse rotation)."]
20644 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20645 pub rpm: [i32; 4],
20646 #[doc = "Voltage measured from each ESC."]
20647 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20648 pub voltage: [f32; 4],
20649 #[doc = "Current measured from each ESC."]
20650 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20651 pub current: [f32; 4],
20652 #[doc = "Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4."]
20653 pub index: u8,
20654}
20655impl ESC_STATUS_DATA {
20656 pub const ENCODED_LEN: usize = 57usize;
20657 pub const DEFAULT: Self = Self {
20658 time_usec: 0_u64,
20659 rpm: [0_i32; 4usize],
20660 voltage: [0.0_f32; 4usize],
20661 current: [0.0_f32; 4usize],
20662 index: 0_u8,
20663 };
20664 #[cfg(feature = "arbitrary")]
20665 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20666 use arbitrary::{Arbitrary, Unstructured};
20667 let mut buf = [0u8; 1024];
20668 rng.fill_bytes(&mut buf);
20669 let mut unstructured = Unstructured::new(&buf);
20670 Self::arbitrary(&mut unstructured).unwrap_or_default()
20671 }
20672}
20673impl Default for ESC_STATUS_DATA {
20674 fn default() -> Self {
20675 Self::DEFAULT.clone()
20676 }
20677}
20678impl MessageData for ESC_STATUS_DATA {
20679 type Message = MavMessage;
20680 const ID: u32 = 291u32;
20681 const NAME: &'static str = "ESC_STATUS";
20682 const EXTRA_CRC: u8 = 10u8;
20683 const ENCODED_LEN: usize = 57usize;
20684 fn deser(
20685 _version: MavlinkVersion,
20686 __input: &[u8],
20687 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20688 let avail_len = __input.len();
20689 let mut payload_buf = [0; Self::ENCODED_LEN];
20690 let mut buf = if avail_len < Self::ENCODED_LEN {
20691 payload_buf[0..avail_len].copy_from_slice(__input);
20692 Bytes::new(&payload_buf)
20693 } else {
20694 Bytes::new(__input)
20695 };
20696 let mut __struct = Self::default();
20697 __struct.time_usec = buf.get_u64_le();
20698 for v in &mut __struct.rpm {
20699 let val = buf.get_i32_le();
20700 *v = val;
20701 }
20702 for v in &mut __struct.voltage {
20703 let val = buf.get_f32_le();
20704 *v = val;
20705 }
20706 for v in &mut __struct.current {
20707 let val = buf.get_f32_le();
20708 *v = val;
20709 }
20710 __struct.index = buf.get_u8();
20711 Ok(__struct)
20712 }
20713 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20714 let mut __tmp = BytesMut::new(bytes);
20715 #[allow(clippy::absurd_extreme_comparisons)]
20716 #[allow(unused_comparisons)]
20717 if __tmp.remaining() < Self::ENCODED_LEN {
20718 panic!(
20719 "buffer is too small (need {} bytes, but got {})",
20720 Self::ENCODED_LEN,
20721 __tmp.remaining(),
20722 )
20723 }
20724 __tmp.put_u64_le(self.time_usec);
20725 for val in &self.rpm {
20726 __tmp.put_i32_le(*val);
20727 }
20728 for val in &self.voltage {
20729 __tmp.put_f32_le(*val);
20730 }
20731 for val in &self.current {
20732 __tmp.put_f32_le(*val);
20733 }
20734 __tmp.put_u8(self.index);
20735 if matches!(version, MavlinkVersion::V2) {
20736 let len = __tmp.len();
20737 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20738 } else {
20739 __tmp.len()
20740 }
20741 }
20742}
20743#[doc = "id: 320"]
20744#[doc = "Request to read the value of a parameter with either the param_id string id or param_index. PARAM_EXT_VALUE should be emitted in response."]
20745#[derive(Debug, Clone, PartialEq)]
20746#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20747#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20748pub struct PARAM_EXT_REQUEST_READ_DATA {
20749 #[doc = "Parameter index. Set to -1 to use the Parameter ID field as identifier (else param_id will be ignored)"]
20750 pub param_index: i16,
20751 #[doc = "System ID"]
20752 pub target_system: u8,
20753 #[doc = "Component ID"]
20754 pub target_component: u8,
20755 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
20756 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
20757 pub param_id: [u8; 16],
20758}
20759impl PARAM_EXT_REQUEST_READ_DATA {
20760 pub const ENCODED_LEN: usize = 20usize;
20761 pub const DEFAULT: Self = Self {
20762 param_index: 0_i16,
20763 target_system: 0_u8,
20764 target_component: 0_u8,
20765 param_id: [0_u8; 16usize],
20766 };
20767 #[cfg(feature = "arbitrary")]
20768 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20769 use arbitrary::{Arbitrary, Unstructured};
20770 let mut buf = [0u8; 1024];
20771 rng.fill_bytes(&mut buf);
20772 let mut unstructured = Unstructured::new(&buf);
20773 Self::arbitrary(&mut unstructured).unwrap_or_default()
20774 }
20775}
20776impl Default for PARAM_EXT_REQUEST_READ_DATA {
20777 fn default() -> Self {
20778 Self::DEFAULT.clone()
20779 }
20780}
20781impl MessageData for PARAM_EXT_REQUEST_READ_DATA {
20782 type Message = MavMessage;
20783 const ID: u32 = 320u32;
20784 const NAME: &'static str = "PARAM_EXT_REQUEST_READ";
20785 const EXTRA_CRC: u8 = 243u8;
20786 const ENCODED_LEN: usize = 20usize;
20787 fn deser(
20788 _version: MavlinkVersion,
20789 __input: &[u8],
20790 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20791 let avail_len = __input.len();
20792 let mut payload_buf = [0; Self::ENCODED_LEN];
20793 let mut buf = if avail_len < Self::ENCODED_LEN {
20794 payload_buf[0..avail_len].copy_from_slice(__input);
20795 Bytes::new(&payload_buf)
20796 } else {
20797 Bytes::new(__input)
20798 };
20799 let mut __struct = Self::default();
20800 __struct.param_index = buf.get_i16_le();
20801 __struct.target_system = buf.get_u8();
20802 __struct.target_component = buf.get_u8();
20803 for v in &mut __struct.param_id {
20804 let val = buf.get_u8();
20805 *v = val;
20806 }
20807 Ok(__struct)
20808 }
20809 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20810 let mut __tmp = BytesMut::new(bytes);
20811 #[allow(clippy::absurd_extreme_comparisons)]
20812 #[allow(unused_comparisons)]
20813 if __tmp.remaining() < Self::ENCODED_LEN {
20814 panic!(
20815 "buffer is too small (need {} bytes, but got {})",
20816 Self::ENCODED_LEN,
20817 __tmp.remaining(),
20818 )
20819 }
20820 __tmp.put_i16_le(self.param_index);
20821 __tmp.put_u8(self.target_system);
20822 __tmp.put_u8(self.target_component);
20823 for val in &self.param_id {
20824 __tmp.put_u8(*val);
20825 }
20826 if matches!(version, MavlinkVersion::V2) {
20827 let len = __tmp.len();
20828 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20829 } else {
20830 __tmp.len()
20831 }
20832 }
20833}
20834#[doc = "id: 129"]
20835#[doc = "The RAW IMU readings for 3rd 9DOF sensor setup. This message should contain the scaled values to the described units."]
20836#[derive(Debug, Clone, PartialEq)]
20837#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20838#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20839pub struct SCALED_IMU3_DATA {
20840 #[doc = "Timestamp (time since system boot)."]
20841 pub time_boot_ms: u32,
20842 #[doc = "X acceleration"]
20843 pub xacc: i16,
20844 #[doc = "Y acceleration"]
20845 pub yacc: i16,
20846 #[doc = "Z acceleration"]
20847 pub zacc: i16,
20848 #[doc = "Angular speed around X axis"]
20849 pub xgyro: i16,
20850 #[doc = "Angular speed around Y axis"]
20851 pub ygyro: i16,
20852 #[doc = "Angular speed around Z axis"]
20853 pub zgyro: i16,
20854 #[doc = "X Magnetic field"]
20855 pub xmag: i16,
20856 #[doc = "Y Magnetic field"]
20857 pub ymag: i16,
20858 #[doc = "Z Magnetic field"]
20859 pub zmag: i16,
20860 #[doc = "Temperature, 0: IMU does not provide temperature values. If the IMU is at 0C it must send 1 (0.01C)."]
20861 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
20862 pub temperature: i16,
20863}
20864impl SCALED_IMU3_DATA {
20865 pub const ENCODED_LEN: usize = 24usize;
20866 pub const DEFAULT: Self = Self {
20867 time_boot_ms: 0_u32,
20868 xacc: 0_i16,
20869 yacc: 0_i16,
20870 zacc: 0_i16,
20871 xgyro: 0_i16,
20872 ygyro: 0_i16,
20873 zgyro: 0_i16,
20874 xmag: 0_i16,
20875 ymag: 0_i16,
20876 zmag: 0_i16,
20877 temperature: 0_i16,
20878 };
20879 #[cfg(feature = "arbitrary")]
20880 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20881 use arbitrary::{Arbitrary, Unstructured};
20882 let mut buf = [0u8; 1024];
20883 rng.fill_bytes(&mut buf);
20884 let mut unstructured = Unstructured::new(&buf);
20885 Self::arbitrary(&mut unstructured).unwrap_or_default()
20886 }
20887}
20888impl Default for SCALED_IMU3_DATA {
20889 fn default() -> Self {
20890 Self::DEFAULT.clone()
20891 }
20892}
20893impl MessageData for SCALED_IMU3_DATA {
20894 type Message = MavMessage;
20895 const ID: u32 = 129u32;
20896 const NAME: &'static str = "SCALED_IMU3";
20897 const EXTRA_CRC: u8 = 46u8;
20898 const ENCODED_LEN: usize = 24usize;
20899 fn deser(
20900 _version: MavlinkVersion,
20901 __input: &[u8],
20902 ) -> Result<Self, ::mavlink_core::error::ParserError> {
20903 let avail_len = __input.len();
20904 let mut payload_buf = [0; Self::ENCODED_LEN];
20905 let mut buf = if avail_len < Self::ENCODED_LEN {
20906 payload_buf[0..avail_len].copy_from_slice(__input);
20907 Bytes::new(&payload_buf)
20908 } else {
20909 Bytes::new(__input)
20910 };
20911 let mut __struct = Self::default();
20912 __struct.time_boot_ms = buf.get_u32_le();
20913 __struct.xacc = buf.get_i16_le();
20914 __struct.yacc = buf.get_i16_le();
20915 __struct.zacc = buf.get_i16_le();
20916 __struct.xgyro = buf.get_i16_le();
20917 __struct.ygyro = buf.get_i16_le();
20918 __struct.zgyro = buf.get_i16_le();
20919 __struct.xmag = buf.get_i16_le();
20920 __struct.ymag = buf.get_i16_le();
20921 __struct.zmag = buf.get_i16_le();
20922 __struct.temperature = buf.get_i16_le();
20923 Ok(__struct)
20924 }
20925 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
20926 let mut __tmp = BytesMut::new(bytes);
20927 #[allow(clippy::absurd_extreme_comparisons)]
20928 #[allow(unused_comparisons)]
20929 if __tmp.remaining() < Self::ENCODED_LEN {
20930 panic!(
20931 "buffer is too small (need {} bytes, but got {})",
20932 Self::ENCODED_LEN,
20933 __tmp.remaining(),
20934 )
20935 }
20936 __tmp.put_u32_le(self.time_boot_ms);
20937 __tmp.put_i16_le(self.xacc);
20938 __tmp.put_i16_le(self.yacc);
20939 __tmp.put_i16_le(self.zacc);
20940 __tmp.put_i16_le(self.xgyro);
20941 __tmp.put_i16_le(self.ygyro);
20942 __tmp.put_i16_le(self.zgyro);
20943 __tmp.put_i16_le(self.xmag);
20944 __tmp.put_i16_le(self.ymag);
20945 __tmp.put_i16_le(self.zmag);
20946 __tmp.put_i16_le(self.temperature);
20947 if matches!(version, MavlinkVersion::V2) {
20948 let len = __tmp.len();
20949 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
20950 } else {
20951 __tmp.len()
20952 }
20953 }
20954}
20955#[doc = "id: 230"]
20956#[doc = "Estimator status message including flags, innovation test ratios and estimated accuracies. The flags message is an integer bitmask containing information on which EKF outputs are valid. See the ESTIMATOR_STATUS_FLAGS enum definition for further information. The innovation test ratios show the magnitude of the sensor innovation divided by the innovation check threshold. Under normal operation the innovation test ratios should be below 0.5 with occasional values up to 1.0. Values greater than 1.0 should be rare under normal operation and indicate that a measurement has been rejected by the filter. The user should be notified if an innovation test ratio greater than 1.0 is recorded. Notifications for values in the range between 0.5 and 1.0 should be optional and controllable by the user."]
20957#[derive(Debug, Clone, PartialEq)]
20958#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
20959#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
20960pub struct ESTIMATOR_STATUS_DATA {
20961 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
20962 pub time_usec: u64,
20963 #[doc = "Velocity innovation test ratio"]
20964 pub vel_ratio: f32,
20965 #[doc = "Horizontal position innovation test ratio"]
20966 pub pos_horiz_ratio: f32,
20967 #[doc = "Vertical position innovation test ratio"]
20968 pub pos_vert_ratio: f32,
20969 #[doc = "Magnetometer innovation test ratio"]
20970 pub mag_ratio: f32,
20971 #[doc = "Height above terrain innovation test ratio"]
20972 pub hagl_ratio: f32,
20973 #[doc = "True airspeed innovation test ratio"]
20974 pub tas_ratio: f32,
20975 #[doc = "Horizontal position 1-STD accuracy relative to the EKF local origin"]
20976 pub pos_horiz_accuracy: f32,
20977 #[doc = "Vertical position 1-STD accuracy relative to the EKF local origin"]
20978 pub pos_vert_accuracy: f32,
20979 #[doc = "Bitmap indicating which EKF outputs are valid."]
20980 pub flags: EstimatorStatusFlags,
20981}
20982impl ESTIMATOR_STATUS_DATA {
20983 pub const ENCODED_LEN: usize = 42usize;
20984 pub const DEFAULT: Self = Self {
20985 time_usec: 0_u64,
20986 vel_ratio: 0.0_f32,
20987 pos_horiz_ratio: 0.0_f32,
20988 pos_vert_ratio: 0.0_f32,
20989 mag_ratio: 0.0_f32,
20990 hagl_ratio: 0.0_f32,
20991 tas_ratio: 0.0_f32,
20992 pos_horiz_accuracy: 0.0_f32,
20993 pos_vert_accuracy: 0.0_f32,
20994 flags: EstimatorStatusFlags::DEFAULT,
20995 };
20996 #[cfg(feature = "arbitrary")]
20997 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
20998 use arbitrary::{Arbitrary, Unstructured};
20999 let mut buf = [0u8; 1024];
21000 rng.fill_bytes(&mut buf);
21001 let mut unstructured = Unstructured::new(&buf);
21002 Self::arbitrary(&mut unstructured).unwrap_or_default()
21003 }
21004}
21005impl Default for ESTIMATOR_STATUS_DATA {
21006 fn default() -> Self {
21007 Self::DEFAULT.clone()
21008 }
21009}
21010impl MessageData for ESTIMATOR_STATUS_DATA {
21011 type Message = MavMessage;
21012 const ID: u32 = 230u32;
21013 const NAME: &'static str = "ESTIMATOR_STATUS";
21014 const EXTRA_CRC: u8 = 163u8;
21015 const ENCODED_LEN: usize = 42usize;
21016 fn deser(
21017 _version: MavlinkVersion,
21018 __input: &[u8],
21019 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21020 let avail_len = __input.len();
21021 let mut payload_buf = [0; Self::ENCODED_LEN];
21022 let mut buf = if avail_len < Self::ENCODED_LEN {
21023 payload_buf[0..avail_len].copy_from_slice(__input);
21024 Bytes::new(&payload_buf)
21025 } else {
21026 Bytes::new(__input)
21027 };
21028 let mut __struct = Self::default();
21029 __struct.time_usec = buf.get_u64_le();
21030 __struct.vel_ratio = buf.get_f32_le();
21031 __struct.pos_horiz_ratio = buf.get_f32_le();
21032 __struct.pos_vert_ratio = buf.get_f32_le();
21033 __struct.mag_ratio = buf.get_f32_le();
21034 __struct.hagl_ratio = buf.get_f32_le();
21035 __struct.tas_ratio = buf.get_f32_le();
21036 __struct.pos_horiz_accuracy = buf.get_f32_le();
21037 __struct.pos_vert_accuracy = buf.get_f32_le();
21038 let tmp = buf.get_u16_le();
21039 __struct.flags = EstimatorStatusFlags::from_bits(tmp & EstimatorStatusFlags::all().bits())
21040 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
21041 flag_type: "EstimatorStatusFlags",
21042 value: tmp as u32,
21043 })?;
21044 Ok(__struct)
21045 }
21046 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21047 let mut __tmp = BytesMut::new(bytes);
21048 #[allow(clippy::absurd_extreme_comparisons)]
21049 #[allow(unused_comparisons)]
21050 if __tmp.remaining() < Self::ENCODED_LEN {
21051 panic!(
21052 "buffer is too small (need {} bytes, but got {})",
21053 Self::ENCODED_LEN,
21054 __tmp.remaining(),
21055 )
21056 }
21057 __tmp.put_u64_le(self.time_usec);
21058 __tmp.put_f32_le(self.vel_ratio);
21059 __tmp.put_f32_le(self.pos_horiz_ratio);
21060 __tmp.put_f32_le(self.pos_vert_ratio);
21061 __tmp.put_f32_le(self.mag_ratio);
21062 __tmp.put_f32_le(self.hagl_ratio);
21063 __tmp.put_f32_le(self.tas_ratio);
21064 __tmp.put_f32_le(self.pos_horiz_accuracy);
21065 __tmp.put_f32_le(self.pos_vert_accuracy);
21066 __tmp.put_u16_le(self.flags.bits());
21067 if matches!(version, MavlinkVersion::V2) {
21068 let len = __tmp.len();
21069 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21070 } else {
21071 __tmp.len()
21072 }
21073 }
21074}
21075#[doc = "id: 324"]
21076#[doc = "Response from a PARAM_EXT_SET message."]
21077#[derive(Debug, Clone, PartialEq)]
21078#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21079#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21080pub struct PARAM_EXT_ACK_DATA {
21081 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
21082 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21083 pub param_id: [u8; 16],
21084 #[doc = "Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)"]
21085 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21086 pub param_value: [u8; 128],
21087 #[doc = "Parameter type."]
21088 pub param_type: MavParamExtType,
21089 #[doc = "Result code."]
21090 pub param_result: ParamAck,
21091}
21092impl PARAM_EXT_ACK_DATA {
21093 pub const ENCODED_LEN: usize = 146usize;
21094 pub const DEFAULT: Self = Self {
21095 param_id: [0_u8; 16usize],
21096 param_value: [0_u8; 128usize],
21097 param_type: MavParamExtType::DEFAULT,
21098 param_result: ParamAck::DEFAULT,
21099 };
21100 #[cfg(feature = "arbitrary")]
21101 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21102 use arbitrary::{Arbitrary, Unstructured};
21103 let mut buf = [0u8; 1024];
21104 rng.fill_bytes(&mut buf);
21105 let mut unstructured = Unstructured::new(&buf);
21106 Self::arbitrary(&mut unstructured).unwrap_or_default()
21107 }
21108}
21109impl Default for PARAM_EXT_ACK_DATA {
21110 fn default() -> Self {
21111 Self::DEFAULT.clone()
21112 }
21113}
21114impl MessageData for PARAM_EXT_ACK_DATA {
21115 type Message = MavMessage;
21116 const ID: u32 = 324u32;
21117 const NAME: &'static str = "PARAM_EXT_ACK";
21118 const EXTRA_CRC: u8 = 132u8;
21119 const ENCODED_LEN: usize = 146usize;
21120 fn deser(
21121 _version: MavlinkVersion,
21122 __input: &[u8],
21123 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21124 let avail_len = __input.len();
21125 let mut payload_buf = [0; Self::ENCODED_LEN];
21126 let mut buf = if avail_len < Self::ENCODED_LEN {
21127 payload_buf[0..avail_len].copy_from_slice(__input);
21128 Bytes::new(&payload_buf)
21129 } else {
21130 Bytes::new(__input)
21131 };
21132 let mut __struct = Self::default();
21133 for v in &mut __struct.param_id {
21134 let val = buf.get_u8();
21135 *v = val;
21136 }
21137 for v in &mut __struct.param_value {
21138 let val = buf.get_u8();
21139 *v = val;
21140 }
21141 let tmp = buf.get_u8();
21142 __struct.param_type =
21143 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21144 enum_type: "MavParamExtType",
21145 value: tmp as u32,
21146 })?;
21147 let tmp = buf.get_u8();
21148 __struct.param_result =
21149 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21150 enum_type: "ParamAck",
21151 value: tmp as u32,
21152 })?;
21153 Ok(__struct)
21154 }
21155 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21156 let mut __tmp = BytesMut::new(bytes);
21157 #[allow(clippy::absurd_extreme_comparisons)]
21158 #[allow(unused_comparisons)]
21159 if __tmp.remaining() < Self::ENCODED_LEN {
21160 panic!(
21161 "buffer is too small (need {} bytes, but got {})",
21162 Self::ENCODED_LEN,
21163 __tmp.remaining(),
21164 )
21165 }
21166 for val in &self.param_id {
21167 __tmp.put_u8(*val);
21168 }
21169 for val in &self.param_value {
21170 __tmp.put_u8(*val);
21171 }
21172 __tmp.put_u8(self.param_type as u8);
21173 __tmp.put_u8(self.param_result as u8);
21174 if matches!(version, MavlinkVersion::V2) {
21175 let len = __tmp.len();
21176 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21177 } else {
21178 __tmp.len()
21179 }
21180 }
21181}
21182#[doc = "id: 248"]
21183#[doc = "Message implementing parts of the V2 payload specs in V1 frames for transitional support."]
21184#[derive(Debug, Clone, PartialEq)]
21185#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21186#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21187pub struct V2_EXTENSION_DATA {
21188 #[doc = "A code that identifies the software component that understands this message (analogous to USB device classes or mime type strings). If this code is less than 32768, it is considered a 'registered' protocol extension and the corresponding entry should be added to <https://github.com/mavlink/mavlink/definition_files/extension_message_ids.xml>. Software creators can register blocks of message IDs as needed (useful for GCS specific metadata, etc...). Message_types greater than 32767 are considered local experiments and should not be checked in to any widely distributed codebase."]
21189 pub message_type: u16,
21190 #[doc = "Network ID (0 for broadcast)"]
21191 pub target_network: u8,
21192 #[doc = "System ID (0 for broadcast)"]
21193 pub target_system: u8,
21194 #[doc = "Component ID (0 for broadcast)"]
21195 pub target_component: u8,
21196 #[doc = "Variable length payload. The length must be encoded in the payload as part of the message_type protocol, e.g. by including the length as payload data, or by terminating the payload data with a non-zero marker. This is required in order to reconstruct zero-terminated payloads that are (or otherwise would be) trimmed by MAVLink 2 empty-byte truncation. The entire content of the payload block is opaque unless you understand the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the MAVLink specification."]
21197 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21198 pub payload: [u8; 249],
21199}
21200impl V2_EXTENSION_DATA {
21201 pub const ENCODED_LEN: usize = 254usize;
21202 pub const DEFAULT: Self = Self {
21203 message_type: 0_u16,
21204 target_network: 0_u8,
21205 target_system: 0_u8,
21206 target_component: 0_u8,
21207 payload: [0_u8; 249usize],
21208 };
21209 #[cfg(feature = "arbitrary")]
21210 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21211 use arbitrary::{Arbitrary, Unstructured};
21212 let mut buf = [0u8; 1024];
21213 rng.fill_bytes(&mut buf);
21214 let mut unstructured = Unstructured::new(&buf);
21215 Self::arbitrary(&mut unstructured).unwrap_or_default()
21216 }
21217}
21218impl Default for V2_EXTENSION_DATA {
21219 fn default() -> Self {
21220 Self::DEFAULT.clone()
21221 }
21222}
21223impl MessageData for V2_EXTENSION_DATA {
21224 type Message = MavMessage;
21225 const ID: u32 = 248u32;
21226 const NAME: &'static str = "V2_EXTENSION";
21227 const EXTRA_CRC: u8 = 8u8;
21228 const ENCODED_LEN: usize = 254usize;
21229 fn deser(
21230 _version: MavlinkVersion,
21231 __input: &[u8],
21232 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21233 let avail_len = __input.len();
21234 let mut payload_buf = [0; Self::ENCODED_LEN];
21235 let mut buf = if avail_len < Self::ENCODED_LEN {
21236 payload_buf[0..avail_len].copy_from_slice(__input);
21237 Bytes::new(&payload_buf)
21238 } else {
21239 Bytes::new(__input)
21240 };
21241 let mut __struct = Self::default();
21242 __struct.message_type = buf.get_u16_le();
21243 __struct.target_network = buf.get_u8();
21244 __struct.target_system = buf.get_u8();
21245 __struct.target_component = buf.get_u8();
21246 for v in &mut __struct.payload {
21247 let val = buf.get_u8();
21248 *v = val;
21249 }
21250 Ok(__struct)
21251 }
21252 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21253 let mut __tmp = BytesMut::new(bytes);
21254 #[allow(clippy::absurd_extreme_comparisons)]
21255 #[allow(unused_comparisons)]
21256 if __tmp.remaining() < Self::ENCODED_LEN {
21257 panic!(
21258 "buffer is too small (need {} bytes, but got {})",
21259 Self::ENCODED_LEN,
21260 __tmp.remaining(),
21261 )
21262 }
21263 __tmp.put_u16_le(self.message_type);
21264 __tmp.put_u8(self.target_network);
21265 __tmp.put_u8(self.target_system);
21266 __tmp.put_u8(self.target_component);
21267 for val in &self.payload {
21268 __tmp.put_u8(*val);
21269 }
21270 if matches!(version, MavlinkVersion::V2) {
21271 let len = __tmp.len();
21272 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21273 } else {
21274 __tmp.len()
21275 }
21276 }
21277}
21278#[doc = "id: 139"]
21279#[doc = "Set the vehicle attitude and body angular rates."]
21280#[derive(Debug, Clone, PartialEq)]
21281#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21282#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21283pub struct SET_ACTUATOR_CONTROL_TARGET_DATA {
21284 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
21285 pub time_usec: u64,
21286 #[doc = "Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs."]
21287 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21288 pub controls: [f32; 8],
21289 #[doc = "Actuator group. The \"_mlx\" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances."]
21290 pub group_mlx: u8,
21291 #[doc = "System ID"]
21292 pub target_system: u8,
21293 #[doc = "Component ID"]
21294 pub target_component: u8,
21295}
21296impl SET_ACTUATOR_CONTROL_TARGET_DATA {
21297 pub const ENCODED_LEN: usize = 43usize;
21298 pub const DEFAULT: Self = Self {
21299 time_usec: 0_u64,
21300 controls: [0.0_f32; 8usize],
21301 group_mlx: 0_u8,
21302 target_system: 0_u8,
21303 target_component: 0_u8,
21304 };
21305 #[cfg(feature = "arbitrary")]
21306 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21307 use arbitrary::{Arbitrary, Unstructured};
21308 let mut buf = [0u8; 1024];
21309 rng.fill_bytes(&mut buf);
21310 let mut unstructured = Unstructured::new(&buf);
21311 Self::arbitrary(&mut unstructured).unwrap_or_default()
21312 }
21313}
21314impl Default for SET_ACTUATOR_CONTROL_TARGET_DATA {
21315 fn default() -> Self {
21316 Self::DEFAULT.clone()
21317 }
21318}
21319impl MessageData for SET_ACTUATOR_CONTROL_TARGET_DATA {
21320 type Message = MavMessage;
21321 const ID: u32 = 139u32;
21322 const NAME: &'static str = "SET_ACTUATOR_CONTROL_TARGET";
21323 const EXTRA_CRC: u8 = 168u8;
21324 const ENCODED_LEN: usize = 43usize;
21325 fn deser(
21326 _version: MavlinkVersion,
21327 __input: &[u8],
21328 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21329 let avail_len = __input.len();
21330 let mut payload_buf = [0; Self::ENCODED_LEN];
21331 let mut buf = if avail_len < Self::ENCODED_LEN {
21332 payload_buf[0..avail_len].copy_from_slice(__input);
21333 Bytes::new(&payload_buf)
21334 } else {
21335 Bytes::new(__input)
21336 };
21337 let mut __struct = Self::default();
21338 __struct.time_usec = buf.get_u64_le();
21339 for v in &mut __struct.controls {
21340 let val = buf.get_f32_le();
21341 *v = val;
21342 }
21343 __struct.group_mlx = buf.get_u8();
21344 __struct.target_system = buf.get_u8();
21345 __struct.target_component = buf.get_u8();
21346 Ok(__struct)
21347 }
21348 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21349 let mut __tmp = BytesMut::new(bytes);
21350 #[allow(clippy::absurd_extreme_comparisons)]
21351 #[allow(unused_comparisons)]
21352 if __tmp.remaining() < Self::ENCODED_LEN {
21353 panic!(
21354 "buffer is too small (need {} bytes, but got {})",
21355 Self::ENCODED_LEN,
21356 __tmp.remaining(),
21357 )
21358 }
21359 __tmp.put_u64_le(self.time_usec);
21360 for val in &self.controls {
21361 __tmp.put_f32_le(*val);
21362 }
21363 __tmp.put_u8(self.group_mlx);
21364 __tmp.put_u8(self.target_system);
21365 __tmp.put_u8(self.target_component);
21366 if matches!(version, MavlinkVersion::V2) {
21367 let len = __tmp.len();
21368 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21369 } else {
21370 __tmp.len()
21371 }
21372 }
21373}
21374#[doc = "id: 70"]
21375#[doc = "The RAW values of the RC channels sent to the MAV to override info received from the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification. Note carefully the semantic differences between the first 8 channels and the subsequent channels."]
21376#[derive(Debug, Clone, PartialEq)]
21377#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21378#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21379pub struct RC_CHANNELS_OVERRIDE_DATA {
21380 #[doc = "RC channel 1 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
21381 pub chan1_raw: u16,
21382 #[doc = "RC channel 2 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
21383 pub chan2_raw: u16,
21384 #[doc = "RC channel 3 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
21385 pub chan3_raw: u16,
21386 #[doc = "RC channel 4 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
21387 pub chan4_raw: u16,
21388 #[doc = "RC channel 5 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
21389 pub chan5_raw: u16,
21390 #[doc = "RC channel 6 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
21391 pub chan6_raw: u16,
21392 #[doc = "RC channel 7 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
21393 pub chan7_raw: u16,
21394 #[doc = "RC channel 8 value. A value of UINT16_MAX means to ignore this field. A value of 0 means to release this channel back to the RC radio."]
21395 pub chan8_raw: u16,
21396 #[doc = "System ID"]
21397 pub target_system: u8,
21398 #[doc = "Component ID"]
21399 pub target_component: u8,
21400 #[doc = "RC channel 9 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21401 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21402 pub chan9_raw: u16,
21403 #[doc = "RC channel 10 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21404 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21405 pub chan10_raw: u16,
21406 #[doc = "RC channel 11 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21407 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21408 pub chan11_raw: u16,
21409 #[doc = "RC channel 12 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21410 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21411 pub chan12_raw: u16,
21412 #[doc = "RC channel 13 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21413 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21414 pub chan13_raw: u16,
21415 #[doc = "RC channel 14 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21416 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21417 pub chan14_raw: u16,
21418 #[doc = "RC channel 15 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21419 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21420 pub chan15_raw: u16,
21421 #[doc = "RC channel 16 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21422 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21423 pub chan16_raw: u16,
21424 #[doc = "RC channel 17 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21425 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21426 pub chan17_raw: u16,
21427 #[doc = "RC channel 18 value. A value of 0 or UINT16_MAX means to ignore this field. A value of UINT16_MAX-1 means to release this channel back to the RC radio."]
21428 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
21429 pub chan18_raw: u16,
21430}
21431impl RC_CHANNELS_OVERRIDE_DATA {
21432 pub const ENCODED_LEN: usize = 38usize;
21433 pub const DEFAULT: Self = Self {
21434 chan1_raw: 0_u16,
21435 chan2_raw: 0_u16,
21436 chan3_raw: 0_u16,
21437 chan4_raw: 0_u16,
21438 chan5_raw: 0_u16,
21439 chan6_raw: 0_u16,
21440 chan7_raw: 0_u16,
21441 chan8_raw: 0_u16,
21442 target_system: 0_u8,
21443 target_component: 0_u8,
21444 chan9_raw: 0_u16,
21445 chan10_raw: 0_u16,
21446 chan11_raw: 0_u16,
21447 chan12_raw: 0_u16,
21448 chan13_raw: 0_u16,
21449 chan14_raw: 0_u16,
21450 chan15_raw: 0_u16,
21451 chan16_raw: 0_u16,
21452 chan17_raw: 0_u16,
21453 chan18_raw: 0_u16,
21454 };
21455 #[cfg(feature = "arbitrary")]
21456 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21457 use arbitrary::{Arbitrary, Unstructured};
21458 let mut buf = [0u8; 1024];
21459 rng.fill_bytes(&mut buf);
21460 let mut unstructured = Unstructured::new(&buf);
21461 Self::arbitrary(&mut unstructured).unwrap_or_default()
21462 }
21463}
21464impl Default for RC_CHANNELS_OVERRIDE_DATA {
21465 fn default() -> Self {
21466 Self::DEFAULT.clone()
21467 }
21468}
21469impl MessageData for RC_CHANNELS_OVERRIDE_DATA {
21470 type Message = MavMessage;
21471 const ID: u32 = 70u32;
21472 const NAME: &'static str = "RC_CHANNELS_OVERRIDE";
21473 const EXTRA_CRC: u8 = 124u8;
21474 const ENCODED_LEN: usize = 38usize;
21475 fn deser(
21476 _version: MavlinkVersion,
21477 __input: &[u8],
21478 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21479 let avail_len = __input.len();
21480 let mut payload_buf = [0; Self::ENCODED_LEN];
21481 let mut buf = if avail_len < Self::ENCODED_LEN {
21482 payload_buf[0..avail_len].copy_from_slice(__input);
21483 Bytes::new(&payload_buf)
21484 } else {
21485 Bytes::new(__input)
21486 };
21487 let mut __struct = Self::default();
21488 __struct.chan1_raw = buf.get_u16_le();
21489 __struct.chan2_raw = buf.get_u16_le();
21490 __struct.chan3_raw = buf.get_u16_le();
21491 __struct.chan4_raw = buf.get_u16_le();
21492 __struct.chan5_raw = buf.get_u16_le();
21493 __struct.chan6_raw = buf.get_u16_le();
21494 __struct.chan7_raw = buf.get_u16_le();
21495 __struct.chan8_raw = buf.get_u16_le();
21496 __struct.target_system = buf.get_u8();
21497 __struct.target_component = buf.get_u8();
21498 __struct.chan9_raw = buf.get_u16_le();
21499 __struct.chan10_raw = buf.get_u16_le();
21500 __struct.chan11_raw = buf.get_u16_le();
21501 __struct.chan12_raw = buf.get_u16_le();
21502 __struct.chan13_raw = buf.get_u16_le();
21503 __struct.chan14_raw = buf.get_u16_le();
21504 __struct.chan15_raw = buf.get_u16_le();
21505 __struct.chan16_raw = buf.get_u16_le();
21506 __struct.chan17_raw = buf.get_u16_le();
21507 __struct.chan18_raw = buf.get_u16_le();
21508 Ok(__struct)
21509 }
21510 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21511 let mut __tmp = BytesMut::new(bytes);
21512 #[allow(clippy::absurd_extreme_comparisons)]
21513 #[allow(unused_comparisons)]
21514 if __tmp.remaining() < Self::ENCODED_LEN {
21515 panic!(
21516 "buffer is too small (need {} bytes, but got {})",
21517 Self::ENCODED_LEN,
21518 __tmp.remaining(),
21519 )
21520 }
21521 __tmp.put_u16_le(self.chan1_raw);
21522 __tmp.put_u16_le(self.chan2_raw);
21523 __tmp.put_u16_le(self.chan3_raw);
21524 __tmp.put_u16_le(self.chan4_raw);
21525 __tmp.put_u16_le(self.chan5_raw);
21526 __tmp.put_u16_le(self.chan6_raw);
21527 __tmp.put_u16_le(self.chan7_raw);
21528 __tmp.put_u16_le(self.chan8_raw);
21529 __tmp.put_u8(self.target_system);
21530 __tmp.put_u8(self.target_component);
21531 __tmp.put_u16_le(self.chan9_raw);
21532 __tmp.put_u16_le(self.chan10_raw);
21533 __tmp.put_u16_le(self.chan11_raw);
21534 __tmp.put_u16_le(self.chan12_raw);
21535 __tmp.put_u16_le(self.chan13_raw);
21536 __tmp.put_u16_le(self.chan14_raw);
21537 __tmp.put_u16_le(self.chan15_raw);
21538 __tmp.put_u16_le(self.chan16_raw);
21539 __tmp.put_u16_le(self.chan17_raw);
21540 __tmp.put_u16_le(self.chan18_raw);
21541 if matches!(version, MavlinkVersion::V2) {
21542 let len = __tmp.len();
21543 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21544 } else {
21545 __tmp.len()
21546 }
21547 }
21548}
21549#[doc = "id: 130"]
21550#[doc = "Handshake message to initiate, control and stop image streaming when using the Image Transmission Protocol: <https://mavlink.io/en/services/image_transmission.html>."]
21551#[derive(Debug, Clone, PartialEq)]
21552#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21553#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21554pub struct DATA_TRANSMISSION_HANDSHAKE_DATA {
21555 #[doc = "total data size (set on ACK only)."]
21556 pub size: u32,
21557 #[doc = "Width of a matrix or image."]
21558 pub width: u16,
21559 #[doc = "Height of a matrix or image."]
21560 pub height: u16,
21561 #[doc = "Number of packets being sent (set on ACK only)."]
21562 pub packets: u16,
21563 #[doc = "Type of requested/acknowledged data."]
21564 pub mavtype: MavlinkDataStreamType,
21565 #[doc = "Payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)."]
21566 pub payload: u8,
21567 #[doc = "JPEG quality. Values: [1-100]."]
21568 pub jpg_quality: u8,
21569}
21570impl DATA_TRANSMISSION_HANDSHAKE_DATA {
21571 pub const ENCODED_LEN: usize = 13usize;
21572 pub const DEFAULT: Self = Self {
21573 size: 0_u32,
21574 width: 0_u16,
21575 height: 0_u16,
21576 packets: 0_u16,
21577 mavtype: MavlinkDataStreamType::DEFAULT,
21578 payload: 0_u8,
21579 jpg_quality: 0_u8,
21580 };
21581 #[cfg(feature = "arbitrary")]
21582 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21583 use arbitrary::{Arbitrary, Unstructured};
21584 let mut buf = [0u8; 1024];
21585 rng.fill_bytes(&mut buf);
21586 let mut unstructured = Unstructured::new(&buf);
21587 Self::arbitrary(&mut unstructured).unwrap_or_default()
21588 }
21589}
21590impl Default for DATA_TRANSMISSION_HANDSHAKE_DATA {
21591 fn default() -> Self {
21592 Self::DEFAULT.clone()
21593 }
21594}
21595impl MessageData for DATA_TRANSMISSION_HANDSHAKE_DATA {
21596 type Message = MavMessage;
21597 const ID: u32 = 130u32;
21598 const NAME: &'static str = "DATA_TRANSMISSION_HANDSHAKE";
21599 const EXTRA_CRC: u8 = 29u8;
21600 const ENCODED_LEN: usize = 13usize;
21601 fn deser(
21602 _version: MavlinkVersion,
21603 __input: &[u8],
21604 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21605 let avail_len = __input.len();
21606 let mut payload_buf = [0; Self::ENCODED_LEN];
21607 let mut buf = if avail_len < Self::ENCODED_LEN {
21608 payload_buf[0..avail_len].copy_from_slice(__input);
21609 Bytes::new(&payload_buf)
21610 } else {
21611 Bytes::new(__input)
21612 };
21613 let mut __struct = Self::default();
21614 __struct.size = buf.get_u32_le();
21615 __struct.width = buf.get_u16_le();
21616 __struct.height = buf.get_u16_le();
21617 __struct.packets = buf.get_u16_le();
21618 let tmp = buf.get_u8();
21619 __struct.mavtype =
21620 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21621 enum_type: "MavlinkDataStreamType",
21622 value: tmp as u32,
21623 })?;
21624 __struct.payload = buf.get_u8();
21625 __struct.jpg_quality = buf.get_u8();
21626 Ok(__struct)
21627 }
21628 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21629 let mut __tmp = BytesMut::new(bytes);
21630 #[allow(clippy::absurd_extreme_comparisons)]
21631 #[allow(unused_comparisons)]
21632 if __tmp.remaining() < Self::ENCODED_LEN {
21633 panic!(
21634 "buffer is too small (need {} bytes, but got {})",
21635 Self::ENCODED_LEN,
21636 __tmp.remaining(),
21637 )
21638 }
21639 __tmp.put_u32_le(self.size);
21640 __tmp.put_u16_le(self.width);
21641 __tmp.put_u16_le(self.height);
21642 __tmp.put_u16_le(self.packets);
21643 __tmp.put_u8(self.mavtype as u8);
21644 __tmp.put_u8(self.payload);
21645 __tmp.put_u8(self.jpg_quality);
21646 if matches!(version, MavlinkVersion::V2) {
21647 let len = __tmp.len();
21648 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21649 } else {
21650 __tmp.len()
21651 }
21652 }
21653}
21654#[doc = "id: 32"]
21655#[doc = "The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
21656#[derive(Debug, Clone, PartialEq)]
21657#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21658#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21659pub struct LOCAL_POSITION_NED_DATA {
21660 #[doc = "Timestamp (time since system boot)."]
21661 pub time_boot_ms: u32,
21662 #[doc = "X Position"]
21663 pub x: f32,
21664 #[doc = "Y Position"]
21665 pub y: f32,
21666 #[doc = "Z Position"]
21667 pub z: f32,
21668 #[doc = "X Speed"]
21669 pub vx: f32,
21670 #[doc = "Y Speed"]
21671 pub vy: f32,
21672 #[doc = "Z Speed"]
21673 pub vz: f32,
21674}
21675impl LOCAL_POSITION_NED_DATA {
21676 pub const ENCODED_LEN: usize = 28usize;
21677 pub const DEFAULT: Self = Self {
21678 time_boot_ms: 0_u32,
21679 x: 0.0_f32,
21680 y: 0.0_f32,
21681 z: 0.0_f32,
21682 vx: 0.0_f32,
21683 vy: 0.0_f32,
21684 vz: 0.0_f32,
21685 };
21686 #[cfg(feature = "arbitrary")]
21687 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21688 use arbitrary::{Arbitrary, Unstructured};
21689 let mut buf = [0u8; 1024];
21690 rng.fill_bytes(&mut buf);
21691 let mut unstructured = Unstructured::new(&buf);
21692 Self::arbitrary(&mut unstructured).unwrap_or_default()
21693 }
21694}
21695impl Default for LOCAL_POSITION_NED_DATA {
21696 fn default() -> Self {
21697 Self::DEFAULT.clone()
21698 }
21699}
21700impl MessageData for LOCAL_POSITION_NED_DATA {
21701 type Message = MavMessage;
21702 const ID: u32 = 32u32;
21703 const NAME: &'static str = "LOCAL_POSITION_NED";
21704 const EXTRA_CRC: u8 = 185u8;
21705 const ENCODED_LEN: usize = 28usize;
21706 fn deser(
21707 _version: MavlinkVersion,
21708 __input: &[u8],
21709 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21710 let avail_len = __input.len();
21711 let mut payload_buf = [0; Self::ENCODED_LEN];
21712 let mut buf = if avail_len < Self::ENCODED_LEN {
21713 payload_buf[0..avail_len].copy_from_slice(__input);
21714 Bytes::new(&payload_buf)
21715 } else {
21716 Bytes::new(__input)
21717 };
21718 let mut __struct = Self::default();
21719 __struct.time_boot_ms = buf.get_u32_le();
21720 __struct.x = buf.get_f32_le();
21721 __struct.y = buf.get_f32_le();
21722 __struct.z = buf.get_f32_le();
21723 __struct.vx = buf.get_f32_le();
21724 __struct.vy = buf.get_f32_le();
21725 __struct.vz = buf.get_f32_le();
21726 Ok(__struct)
21727 }
21728 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21729 let mut __tmp = BytesMut::new(bytes);
21730 #[allow(clippy::absurd_extreme_comparisons)]
21731 #[allow(unused_comparisons)]
21732 if __tmp.remaining() < Self::ENCODED_LEN {
21733 panic!(
21734 "buffer is too small (need {} bytes, but got {})",
21735 Self::ENCODED_LEN,
21736 __tmp.remaining(),
21737 )
21738 }
21739 __tmp.put_u32_le(self.time_boot_ms);
21740 __tmp.put_f32_le(self.x);
21741 __tmp.put_f32_le(self.y);
21742 __tmp.put_f32_le(self.z);
21743 __tmp.put_f32_le(self.vx);
21744 __tmp.put_f32_le(self.vy);
21745 __tmp.put_f32_le(self.vz);
21746 if matches!(version, MavlinkVersion::V2) {
21747 let len = __tmp.len();
21748 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21749 } else {
21750 __tmp.len()
21751 }
21752 }
21753}
21754#[doc = "id: 245"]
21755#[doc = "Provides state for additional features."]
21756#[derive(Debug, Clone, PartialEq)]
21757#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21758#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21759pub struct EXTENDED_SYS_STATE_DATA {
21760 #[doc = "The VTOL state if applicable. Is set to MAV_VTOL_STATE_UNDEFINED if UAV is not in VTOL configuration."]
21761 pub vtol_state: MavVtolState,
21762 #[doc = "The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown."]
21763 pub landed_state: MavLandedState,
21764}
21765impl EXTENDED_SYS_STATE_DATA {
21766 pub const ENCODED_LEN: usize = 2usize;
21767 pub const DEFAULT: Self = Self {
21768 vtol_state: MavVtolState::DEFAULT,
21769 landed_state: MavLandedState::DEFAULT,
21770 };
21771 #[cfg(feature = "arbitrary")]
21772 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21773 use arbitrary::{Arbitrary, Unstructured};
21774 let mut buf = [0u8; 1024];
21775 rng.fill_bytes(&mut buf);
21776 let mut unstructured = Unstructured::new(&buf);
21777 Self::arbitrary(&mut unstructured).unwrap_or_default()
21778 }
21779}
21780impl Default for EXTENDED_SYS_STATE_DATA {
21781 fn default() -> Self {
21782 Self::DEFAULT.clone()
21783 }
21784}
21785impl MessageData for EXTENDED_SYS_STATE_DATA {
21786 type Message = MavMessage;
21787 const ID: u32 = 245u32;
21788 const NAME: &'static str = "EXTENDED_SYS_STATE";
21789 const EXTRA_CRC: u8 = 130u8;
21790 const ENCODED_LEN: usize = 2usize;
21791 fn deser(
21792 _version: MavlinkVersion,
21793 __input: &[u8],
21794 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21795 let avail_len = __input.len();
21796 let mut payload_buf = [0; Self::ENCODED_LEN];
21797 let mut buf = if avail_len < Self::ENCODED_LEN {
21798 payload_buf[0..avail_len].copy_from_slice(__input);
21799 Bytes::new(&payload_buf)
21800 } else {
21801 Bytes::new(__input)
21802 };
21803 let mut __struct = Self::default();
21804 let tmp = buf.get_u8();
21805 __struct.vtol_state =
21806 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21807 enum_type: "MavVtolState",
21808 value: tmp as u32,
21809 })?;
21810 let tmp = buf.get_u8();
21811 __struct.landed_state =
21812 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21813 enum_type: "MavLandedState",
21814 value: tmp as u32,
21815 })?;
21816 Ok(__struct)
21817 }
21818 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21819 let mut __tmp = BytesMut::new(bytes);
21820 #[allow(clippy::absurd_extreme_comparisons)]
21821 #[allow(unused_comparisons)]
21822 if __tmp.remaining() < Self::ENCODED_LEN {
21823 panic!(
21824 "buffer is too small (need {} bytes, but got {})",
21825 Self::ENCODED_LEN,
21826 __tmp.remaining(),
21827 )
21828 }
21829 __tmp.put_u8(self.vtol_state as u8);
21830 __tmp.put_u8(self.landed_state as u8);
21831 if matches!(version, MavlinkVersion::V2) {
21832 let len = __tmp.len();
21833 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21834 } else {
21835 __tmp.len()
21836 }
21837 }
21838}
21839#[doc = "id: 162"]
21840#[doc = "Status of geo-fencing. Sent in extended status stream when fencing enabled."]
21841#[derive(Debug, Clone, PartialEq)]
21842#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21843#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21844pub struct FENCE_STATUS_DATA {
21845 #[doc = "Time (since boot) of last breach."]
21846 pub breach_time: u32,
21847 #[doc = "Number of fence breaches."]
21848 pub breach_count: u16,
21849 #[doc = "Breach status (0 if currently inside fence, 1 if outside)."]
21850 pub breach_status: u8,
21851 #[doc = "Last breach type."]
21852 pub breach_type: FenceBreach,
21853 #[doc = "Active action to prevent fence breach"]
21854 #[cfg_attr(feature = "serde", serde(default))]
21855 pub breach_mitigation: FenceMitigate,
21856}
21857impl FENCE_STATUS_DATA {
21858 pub const ENCODED_LEN: usize = 9usize;
21859 pub const DEFAULT: Self = Self {
21860 breach_time: 0_u32,
21861 breach_count: 0_u16,
21862 breach_status: 0_u8,
21863 breach_type: FenceBreach::DEFAULT,
21864 breach_mitigation: FenceMitigate::DEFAULT,
21865 };
21866 #[cfg(feature = "arbitrary")]
21867 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
21868 use arbitrary::{Arbitrary, Unstructured};
21869 let mut buf = [0u8; 1024];
21870 rng.fill_bytes(&mut buf);
21871 let mut unstructured = Unstructured::new(&buf);
21872 Self::arbitrary(&mut unstructured).unwrap_or_default()
21873 }
21874}
21875impl Default for FENCE_STATUS_DATA {
21876 fn default() -> Self {
21877 Self::DEFAULT.clone()
21878 }
21879}
21880impl MessageData for FENCE_STATUS_DATA {
21881 type Message = MavMessage;
21882 const ID: u32 = 162u32;
21883 const NAME: &'static str = "FENCE_STATUS";
21884 const EXTRA_CRC: u8 = 189u8;
21885 const ENCODED_LEN: usize = 9usize;
21886 fn deser(
21887 _version: MavlinkVersion,
21888 __input: &[u8],
21889 ) -> Result<Self, ::mavlink_core::error::ParserError> {
21890 let avail_len = __input.len();
21891 let mut payload_buf = [0; Self::ENCODED_LEN];
21892 let mut buf = if avail_len < Self::ENCODED_LEN {
21893 payload_buf[0..avail_len].copy_from_slice(__input);
21894 Bytes::new(&payload_buf)
21895 } else {
21896 Bytes::new(__input)
21897 };
21898 let mut __struct = Self::default();
21899 __struct.breach_time = buf.get_u32_le();
21900 __struct.breach_count = buf.get_u16_le();
21901 __struct.breach_status = buf.get_u8();
21902 let tmp = buf.get_u8();
21903 __struct.breach_type =
21904 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21905 enum_type: "FenceBreach",
21906 value: tmp as u32,
21907 })?;
21908 let tmp = buf.get_u8();
21909 __struct.breach_mitigation =
21910 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
21911 enum_type: "FenceMitigate",
21912 value: tmp as u32,
21913 })?;
21914 Ok(__struct)
21915 }
21916 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
21917 let mut __tmp = BytesMut::new(bytes);
21918 #[allow(clippy::absurd_extreme_comparisons)]
21919 #[allow(unused_comparisons)]
21920 if __tmp.remaining() < Self::ENCODED_LEN {
21921 panic!(
21922 "buffer is too small (need {} bytes, but got {})",
21923 Self::ENCODED_LEN,
21924 __tmp.remaining(),
21925 )
21926 }
21927 __tmp.put_u32_le(self.breach_time);
21928 __tmp.put_u16_le(self.breach_count);
21929 __tmp.put_u8(self.breach_status);
21930 __tmp.put_u8(self.breach_type as u8);
21931 __tmp.put_u8(self.breach_mitigation as u8);
21932 if matches!(version, MavlinkVersion::V2) {
21933 let len = __tmp.len();
21934 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
21935 } else {
21936 __tmp.len()
21937 }
21938 }
21939}
21940#[doc = "id: 390"]
21941#[doc = "Hardware status sent by an onboard computer."]
21942#[derive(Debug, Clone, PartialEq)]
21943#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
21944#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
21945pub struct ONBOARD_COMPUTER_STATUS_DATA {
21946 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
21947 pub time_usec: u64,
21948 #[doc = "Time since system boot."]
21949 pub uptime: u32,
21950 #[doc = "Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused."]
21951 pub ram_usage: u32,
21952 #[doc = "Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused."]
21953 pub ram_total: u32,
21954 #[doc = "Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused."]
21955 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21956 pub storage_type: [u32; 4],
21957 #[doc = "Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused."]
21958 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21959 pub storage_usage: [u32; 4],
21960 #[doc = "Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused."]
21961 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21962 pub storage_total: [u32; 4],
21963 #[doc = "Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary"]
21964 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21965 pub link_type: [u32; 6],
21966 #[doc = "Network traffic from the component system. A value of UINT32_MAX implies the field is unused."]
21967 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21968 pub link_tx_rate: [u32; 6],
21969 #[doc = "Network traffic to the component system. A value of UINT32_MAX implies the field is unused."]
21970 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21971 pub link_rx_rate: [u32; 6],
21972 #[doc = "Network capacity from the component system. A value of UINT32_MAX implies the field is unused."]
21973 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21974 pub link_tx_max: [u32; 6],
21975 #[doc = "Network capacity to the component system. A value of UINT32_MAX implies the field is unused."]
21976 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21977 pub link_rx_max: [u32; 6],
21978 #[doc = "Fan speeds. A value of INT16_MAX implies the field is unused."]
21979 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21980 pub fan_speed: [i16; 4],
21981 #[doc = "Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers."]
21982 pub mavtype: u8,
21983 #[doc = "CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
21984 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21985 pub cpu_cores: [u8; 8],
21986 #[doc = "Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
21987 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21988 pub cpu_combined: [u8; 10],
21989 #[doc = "GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused."]
21990 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21991 pub gpu_cores: [u8; 4],
21992 #[doc = "Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused."]
21993 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21994 pub gpu_combined: [u8; 10],
21995 #[doc = "Temperature of the board. A value of INT8_MAX implies the field is unused."]
21996 pub temperature_board: i8,
21997 #[doc = "Temperature of the CPU core. A value of INT8_MAX implies the field is unused."]
21998 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
21999 pub temperature_core: [i8; 8],
22000}
22001impl ONBOARD_COMPUTER_STATUS_DATA {
22002 pub const ENCODED_LEN: usize = 238usize;
22003 pub const DEFAULT: Self = Self {
22004 time_usec: 0_u64,
22005 uptime: 0_u32,
22006 ram_usage: 0_u32,
22007 ram_total: 0_u32,
22008 storage_type: [0_u32; 4usize],
22009 storage_usage: [0_u32; 4usize],
22010 storage_total: [0_u32; 4usize],
22011 link_type: [0_u32; 6usize],
22012 link_tx_rate: [0_u32; 6usize],
22013 link_rx_rate: [0_u32; 6usize],
22014 link_tx_max: [0_u32; 6usize],
22015 link_rx_max: [0_u32; 6usize],
22016 fan_speed: [0_i16; 4usize],
22017 mavtype: 0_u8,
22018 cpu_cores: [0_u8; 8usize],
22019 cpu_combined: [0_u8; 10usize],
22020 gpu_cores: [0_u8; 4usize],
22021 gpu_combined: [0_u8; 10usize],
22022 temperature_board: 0_i8,
22023 temperature_core: [0_i8; 8usize],
22024 };
22025 #[cfg(feature = "arbitrary")]
22026 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22027 use arbitrary::{Arbitrary, Unstructured};
22028 let mut buf = [0u8; 1024];
22029 rng.fill_bytes(&mut buf);
22030 let mut unstructured = Unstructured::new(&buf);
22031 Self::arbitrary(&mut unstructured).unwrap_or_default()
22032 }
22033}
22034impl Default for ONBOARD_COMPUTER_STATUS_DATA {
22035 fn default() -> Self {
22036 Self::DEFAULT.clone()
22037 }
22038}
22039impl MessageData for ONBOARD_COMPUTER_STATUS_DATA {
22040 type Message = MavMessage;
22041 const ID: u32 = 390u32;
22042 const NAME: &'static str = "ONBOARD_COMPUTER_STATUS";
22043 const EXTRA_CRC: u8 = 156u8;
22044 const ENCODED_LEN: usize = 238usize;
22045 fn deser(
22046 _version: MavlinkVersion,
22047 __input: &[u8],
22048 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22049 let avail_len = __input.len();
22050 let mut payload_buf = [0; Self::ENCODED_LEN];
22051 let mut buf = if avail_len < Self::ENCODED_LEN {
22052 payload_buf[0..avail_len].copy_from_slice(__input);
22053 Bytes::new(&payload_buf)
22054 } else {
22055 Bytes::new(__input)
22056 };
22057 let mut __struct = Self::default();
22058 __struct.time_usec = buf.get_u64_le();
22059 __struct.uptime = buf.get_u32_le();
22060 __struct.ram_usage = buf.get_u32_le();
22061 __struct.ram_total = buf.get_u32_le();
22062 for v in &mut __struct.storage_type {
22063 let val = buf.get_u32_le();
22064 *v = val;
22065 }
22066 for v in &mut __struct.storage_usage {
22067 let val = buf.get_u32_le();
22068 *v = val;
22069 }
22070 for v in &mut __struct.storage_total {
22071 let val = buf.get_u32_le();
22072 *v = val;
22073 }
22074 for v in &mut __struct.link_type {
22075 let val = buf.get_u32_le();
22076 *v = val;
22077 }
22078 for v in &mut __struct.link_tx_rate {
22079 let val = buf.get_u32_le();
22080 *v = val;
22081 }
22082 for v in &mut __struct.link_rx_rate {
22083 let val = buf.get_u32_le();
22084 *v = val;
22085 }
22086 for v in &mut __struct.link_tx_max {
22087 let val = buf.get_u32_le();
22088 *v = val;
22089 }
22090 for v in &mut __struct.link_rx_max {
22091 let val = buf.get_u32_le();
22092 *v = val;
22093 }
22094 for v in &mut __struct.fan_speed {
22095 let val = buf.get_i16_le();
22096 *v = val;
22097 }
22098 __struct.mavtype = buf.get_u8();
22099 for v in &mut __struct.cpu_cores {
22100 let val = buf.get_u8();
22101 *v = val;
22102 }
22103 for v in &mut __struct.cpu_combined {
22104 let val = buf.get_u8();
22105 *v = val;
22106 }
22107 for v in &mut __struct.gpu_cores {
22108 let val = buf.get_u8();
22109 *v = val;
22110 }
22111 for v in &mut __struct.gpu_combined {
22112 let val = buf.get_u8();
22113 *v = val;
22114 }
22115 __struct.temperature_board = buf.get_i8();
22116 for v in &mut __struct.temperature_core {
22117 let val = buf.get_i8();
22118 *v = val;
22119 }
22120 Ok(__struct)
22121 }
22122 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22123 let mut __tmp = BytesMut::new(bytes);
22124 #[allow(clippy::absurd_extreme_comparisons)]
22125 #[allow(unused_comparisons)]
22126 if __tmp.remaining() < Self::ENCODED_LEN {
22127 panic!(
22128 "buffer is too small (need {} bytes, but got {})",
22129 Self::ENCODED_LEN,
22130 __tmp.remaining(),
22131 )
22132 }
22133 __tmp.put_u64_le(self.time_usec);
22134 __tmp.put_u32_le(self.uptime);
22135 __tmp.put_u32_le(self.ram_usage);
22136 __tmp.put_u32_le(self.ram_total);
22137 for val in &self.storage_type {
22138 __tmp.put_u32_le(*val);
22139 }
22140 for val in &self.storage_usage {
22141 __tmp.put_u32_le(*val);
22142 }
22143 for val in &self.storage_total {
22144 __tmp.put_u32_le(*val);
22145 }
22146 for val in &self.link_type {
22147 __tmp.put_u32_le(*val);
22148 }
22149 for val in &self.link_tx_rate {
22150 __tmp.put_u32_le(*val);
22151 }
22152 for val in &self.link_rx_rate {
22153 __tmp.put_u32_le(*val);
22154 }
22155 for val in &self.link_tx_max {
22156 __tmp.put_u32_le(*val);
22157 }
22158 for val in &self.link_rx_max {
22159 __tmp.put_u32_le(*val);
22160 }
22161 for val in &self.fan_speed {
22162 __tmp.put_i16_le(*val);
22163 }
22164 __tmp.put_u8(self.mavtype);
22165 for val in &self.cpu_cores {
22166 __tmp.put_u8(*val);
22167 }
22168 for val in &self.cpu_combined {
22169 __tmp.put_u8(*val);
22170 }
22171 for val in &self.gpu_cores {
22172 __tmp.put_u8(*val);
22173 }
22174 for val in &self.gpu_combined {
22175 __tmp.put_u8(*val);
22176 }
22177 __tmp.put_i8(self.temperature_board);
22178 for val in &self.temperature_core {
22179 __tmp.put_i8(*val);
22180 }
22181 if matches!(version, MavlinkVersion::V2) {
22182 let len = __tmp.len();
22183 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22184 } else {
22185 __tmp.len()
22186 }
22187 }
22188}
22189#[doc = "id: 43"]
22190#[doc = "Request the overall list of mission items from the system/component."]
22191#[derive(Debug, Clone, PartialEq)]
22192#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22193#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22194pub struct MISSION_REQUEST_LIST_DATA {
22195 #[doc = "System ID"]
22196 pub target_system: u8,
22197 #[doc = "Component ID"]
22198 pub target_component: u8,
22199 #[doc = "Mission type."]
22200 #[cfg_attr(feature = "serde", serde(default))]
22201 pub mission_type: MavMissionType,
22202}
22203impl MISSION_REQUEST_LIST_DATA {
22204 pub const ENCODED_LEN: usize = 3usize;
22205 pub const DEFAULT: Self = Self {
22206 target_system: 0_u8,
22207 target_component: 0_u8,
22208 mission_type: MavMissionType::DEFAULT,
22209 };
22210 #[cfg(feature = "arbitrary")]
22211 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22212 use arbitrary::{Arbitrary, Unstructured};
22213 let mut buf = [0u8; 1024];
22214 rng.fill_bytes(&mut buf);
22215 let mut unstructured = Unstructured::new(&buf);
22216 Self::arbitrary(&mut unstructured).unwrap_or_default()
22217 }
22218}
22219impl Default for MISSION_REQUEST_LIST_DATA {
22220 fn default() -> Self {
22221 Self::DEFAULT.clone()
22222 }
22223}
22224impl MessageData for MISSION_REQUEST_LIST_DATA {
22225 type Message = MavMessage;
22226 const ID: u32 = 43u32;
22227 const NAME: &'static str = "MISSION_REQUEST_LIST";
22228 const EXTRA_CRC: u8 = 132u8;
22229 const ENCODED_LEN: usize = 3usize;
22230 fn deser(
22231 _version: MavlinkVersion,
22232 __input: &[u8],
22233 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22234 let avail_len = __input.len();
22235 let mut payload_buf = [0; Self::ENCODED_LEN];
22236 let mut buf = if avail_len < Self::ENCODED_LEN {
22237 payload_buf[0..avail_len].copy_from_slice(__input);
22238 Bytes::new(&payload_buf)
22239 } else {
22240 Bytes::new(__input)
22241 };
22242 let mut __struct = Self::default();
22243 __struct.target_system = buf.get_u8();
22244 __struct.target_component = buf.get_u8();
22245 let tmp = buf.get_u8();
22246 __struct.mission_type =
22247 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22248 enum_type: "MavMissionType",
22249 value: tmp as u32,
22250 })?;
22251 Ok(__struct)
22252 }
22253 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22254 let mut __tmp = BytesMut::new(bytes);
22255 #[allow(clippy::absurd_extreme_comparisons)]
22256 #[allow(unused_comparisons)]
22257 if __tmp.remaining() < Self::ENCODED_LEN {
22258 panic!(
22259 "buffer is too small (need {} bytes, but got {})",
22260 Self::ENCODED_LEN,
22261 __tmp.remaining(),
22262 )
22263 }
22264 __tmp.put_u8(self.target_system);
22265 __tmp.put_u8(self.target_component);
22266 __tmp.put_u8(self.mission_type as u8);
22267 if matches!(version, MavlinkVersion::V2) {
22268 let len = __tmp.len();
22269 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22270 } else {
22271 __tmp.len()
22272 }
22273 }
22274}
22275#[doc = "id: 244"]
22276#[doc = "The interval between messages for a particular MAVLink message ID. This message is sent in response to the MAV_CMD_REQUEST_MESSAGE command with param1=244 (this message) and param2=message_id (the id of the message for which the interval is required). \tIt may also be sent in response to MAV_CMD_GET_MESSAGE_INTERVAL. \tThis interface replaces DATA_STREAM."]
22277#[derive(Debug, Clone, PartialEq)]
22278#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22279#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22280pub struct MESSAGE_INTERVAL_DATA {
22281 #[doc = "0 indicates the interval at which it is sent."]
22282 pub interval_us: i32,
22283 #[doc = "The ID of the requested MAVLink message. v1.0 is limited to 254 messages."]
22284 pub message_id: u16,
22285}
22286impl MESSAGE_INTERVAL_DATA {
22287 pub const ENCODED_LEN: usize = 6usize;
22288 pub const DEFAULT: Self = Self {
22289 interval_us: 0_i32,
22290 message_id: 0_u16,
22291 };
22292 #[cfg(feature = "arbitrary")]
22293 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22294 use arbitrary::{Arbitrary, Unstructured};
22295 let mut buf = [0u8; 1024];
22296 rng.fill_bytes(&mut buf);
22297 let mut unstructured = Unstructured::new(&buf);
22298 Self::arbitrary(&mut unstructured).unwrap_or_default()
22299 }
22300}
22301impl Default for MESSAGE_INTERVAL_DATA {
22302 fn default() -> Self {
22303 Self::DEFAULT.clone()
22304 }
22305}
22306impl MessageData for MESSAGE_INTERVAL_DATA {
22307 type Message = MavMessage;
22308 const ID: u32 = 244u32;
22309 const NAME: &'static str = "MESSAGE_INTERVAL";
22310 const EXTRA_CRC: u8 = 95u8;
22311 const ENCODED_LEN: usize = 6usize;
22312 fn deser(
22313 _version: MavlinkVersion,
22314 __input: &[u8],
22315 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22316 let avail_len = __input.len();
22317 let mut payload_buf = [0; Self::ENCODED_LEN];
22318 let mut buf = if avail_len < Self::ENCODED_LEN {
22319 payload_buf[0..avail_len].copy_from_slice(__input);
22320 Bytes::new(&payload_buf)
22321 } else {
22322 Bytes::new(__input)
22323 };
22324 let mut __struct = Self::default();
22325 __struct.interval_us = buf.get_i32_le();
22326 __struct.message_id = buf.get_u16_le();
22327 Ok(__struct)
22328 }
22329 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22330 let mut __tmp = BytesMut::new(bytes);
22331 #[allow(clippy::absurd_extreme_comparisons)]
22332 #[allow(unused_comparisons)]
22333 if __tmp.remaining() < Self::ENCODED_LEN {
22334 panic!(
22335 "buffer is too small (need {} bytes, but got {})",
22336 Self::ENCODED_LEN,
22337 __tmp.remaining(),
22338 )
22339 }
22340 __tmp.put_i32_le(self.interval_us);
22341 __tmp.put_u16_le(self.message_id);
22342 if matches!(version, MavlinkVersion::V2) {
22343 let len = __tmp.len();
22344 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22345 } else {
22346 __tmp.len()
22347 }
22348 }
22349}
22350#[doc = "id: 133"]
22351#[doc = "Request for terrain data and terrain status. See terrain protocol docs: <https://mavlink.io/en/services/terrain.html>."]
22352#[derive(Debug, Clone, PartialEq)]
22353#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22354#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22355pub struct TERRAIN_REQUEST_DATA {
22356 #[doc = "Bitmask of requested 4x4 grids (row major 8x7 array of grids, 56 bits)"]
22357 pub mask: u64,
22358 #[doc = "Latitude of SW corner of first grid"]
22359 pub lat: i32,
22360 #[doc = "Longitude of SW corner of first grid"]
22361 pub lon: i32,
22362 #[doc = "Grid spacing"]
22363 pub grid_spacing: u16,
22364}
22365impl TERRAIN_REQUEST_DATA {
22366 pub const ENCODED_LEN: usize = 18usize;
22367 pub const DEFAULT: Self = Self {
22368 mask: 0_u64,
22369 lat: 0_i32,
22370 lon: 0_i32,
22371 grid_spacing: 0_u16,
22372 };
22373 #[cfg(feature = "arbitrary")]
22374 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22375 use arbitrary::{Arbitrary, Unstructured};
22376 let mut buf = [0u8; 1024];
22377 rng.fill_bytes(&mut buf);
22378 let mut unstructured = Unstructured::new(&buf);
22379 Self::arbitrary(&mut unstructured).unwrap_or_default()
22380 }
22381}
22382impl Default for TERRAIN_REQUEST_DATA {
22383 fn default() -> Self {
22384 Self::DEFAULT.clone()
22385 }
22386}
22387impl MessageData for TERRAIN_REQUEST_DATA {
22388 type Message = MavMessage;
22389 const ID: u32 = 133u32;
22390 const NAME: &'static str = "TERRAIN_REQUEST";
22391 const EXTRA_CRC: u8 = 6u8;
22392 const ENCODED_LEN: usize = 18usize;
22393 fn deser(
22394 _version: MavlinkVersion,
22395 __input: &[u8],
22396 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22397 let avail_len = __input.len();
22398 let mut payload_buf = [0; Self::ENCODED_LEN];
22399 let mut buf = if avail_len < Self::ENCODED_LEN {
22400 payload_buf[0..avail_len].copy_from_slice(__input);
22401 Bytes::new(&payload_buf)
22402 } else {
22403 Bytes::new(__input)
22404 };
22405 let mut __struct = Self::default();
22406 __struct.mask = buf.get_u64_le();
22407 __struct.lat = buf.get_i32_le();
22408 __struct.lon = buf.get_i32_le();
22409 __struct.grid_spacing = buf.get_u16_le();
22410 Ok(__struct)
22411 }
22412 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22413 let mut __tmp = BytesMut::new(bytes);
22414 #[allow(clippy::absurd_extreme_comparisons)]
22415 #[allow(unused_comparisons)]
22416 if __tmp.remaining() < Self::ENCODED_LEN {
22417 panic!(
22418 "buffer is too small (need {} bytes, but got {})",
22419 Self::ENCODED_LEN,
22420 __tmp.remaining(),
22421 )
22422 }
22423 __tmp.put_u64_le(self.mask);
22424 __tmp.put_i32_le(self.lat);
22425 __tmp.put_i32_le(self.lon);
22426 __tmp.put_u16_le(self.grid_spacing);
22427 if matches!(version, MavlinkVersion::V2) {
22428 let len = __tmp.len();
22429 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22430 } else {
22431 __tmp.len()
22432 }
22433 }
22434}
22435#[doc = "id: 143"]
22436#[doc = "Barometer readings for 3rd barometer."]
22437#[derive(Debug, Clone, PartialEq)]
22438#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22439#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22440pub struct SCALED_PRESSURE3_DATA {
22441 #[doc = "Timestamp (time since system boot)."]
22442 pub time_boot_ms: u32,
22443 #[doc = "Absolute pressure"]
22444 pub press_abs: f32,
22445 #[doc = "Differential pressure"]
22446 pub press_diff: f32,
22447 #[doc = "Absolute pressure temperature"]
22448 pub temperature: i16,
22449 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
22450 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22451 pub temperature_press_diff: i16,
22452}
22453impl SCALED_PRESSURE3_DATA {
22454 pub const ENCODED_LEN: usize = 16usize;
22455 pub const DEFAULT: Self = Self {
22456 time_boot_ms: 0_u32,
22457 press_abs: 0.0_f32,
22458 press_diff: 0.0_f32,
22459 temperature: 0_i16,
22460 temperature_press_diff: 0_i16,
22461 };
22462 #[cfg(feature = "arbitrary")]
22463 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22464 use arbitrary::{Arbitrary, Unstructured};
22465 let mut buf = [0u8; 1024];
22466 rng.fill_bytes(&mut buf);
22467 let mut unstructured = Unstructured::new(&buf);
22468 Self::arbitrary(&mut unstructured).unwrap_or_default()
22469 }
22470}
22471impl Default for SCALED_PRESSURE3_DATA {
22472 fn default() -> Self {
22473 Self::DEFAULT.clone()
22474 }
22475}
22476impl MessageData for SCALED_PRESSURE3_DATA {
22477 type Message = MavMessage;
22478 const ID: u32 = 143u32;
22479 const NAME: &'static str = "SCALED_PRESSURE3";
22480 const EXTRA_CRC: u8 = 131u8;
22481 const ENCODED_LEN: usize = 16usize;
22482 fn deser(
22483 _version: MavlinkVersion,
22484 __input: &[u8],
22485 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22486 let avail_len = __input.len();
22487 let mut payload_buf = [0; Self::ENCODED_LEN];
22488 let mut buf = if avail_len < Self::ENCODED_LEN {
22489 payload_buf[0..avail_len].copy_from_slice(__input);
22490 Bytes::new(&payload_buf)
22491 } else {
22492 Bytes::new(__input)
22493 };
22494 let mut __struct = Self::default();
22495 __struct.time_boot_ms = buf.get_u32_le();
22496 __struct.press_abs = buf.get_f32_le();
22497 __struct.press_diff = buf.get_f32_le();
22498 __struct.temperature = buf.get_i16_le();
22499 __struct.temperature_press_diff = buf.get_i16_le();
22500 Ok(__struct)
22501 }
22502 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22503 let mut __tmp = BytesMut::new(bytes);
22504 #[allow(clippy::absurd_extreme_comparisons)]
22505 #[allow(unused_comparisons)]
22506 if __tmp.remaining() < Self::ENCODED_LEN {
22507 panic!(
22508 "buffer is too small (need {} bytes, but got {})",
22509 Self::ENCODED_LEN,
22510 __tmp.remaining(),
22511 )
22512 }
22513 __tmp.put_u32_le(self.time_boot_ms);
22514 __tmp.put_f32_le(self.press_abs);
22515 __tmp.put_f32_le(self.press_diff);
22516 __tmp.put_i16_le(self.temperature);
22517 __tmp.put_i16_le(self.temperature_press_diff);
22518 if matches!(version, MavlinkVersion::V2) {
22519 let len = __tmp.len();
22520 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22521 } else {
22522 __tmp.len()
22523 }
22524 }
22525}
22526#[doc = "id: 412"]
22527#[doc = "Request one or more events to be (re-)sent. If first_sequence==last_sequence, only a single event is requested. Note that first_sequence can be larger than last_sequence (because the sequence number can wrap). Each sequence will trigger an EVENT or EVENT_ERROR response."]
22528#[derive(Debug, Clone, PartialEq)]
22529#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22530#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22531pub struct REQUEST_EVENT_DATA {
22532 #[doc = "First sequence number of the requested event."]
22533 pub first_sequence: u16,
22534 #[doc = "Last sequence number of the requested event."]
22535 pub last_sequence: u16,
22536 #[doc = "System ID"]
22537 pub target_system: u8,
22538 #[doc = "Component ID"]
22539 pub target_component: u8,
22540}
22541impl REQUEST_EVENT_DATA {
22542 pub const ENCODED_LEN: usize = 6usize;
22543 pub const DEFAULT: Self = Self {
22544 first_sequence: 0_u16,
22545 last_sequence: 0_u16,
22546 target_system: 0_u8,
22547 target_component: 0_u8,
22548 };
22549 #[cfg(feature = "arbitrary")]
22550 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22551 use arbitrary::{Arbitrary, Unstructured};
22552 let mut buf = [0u8; 1024];
22553 rng.fill_bytes(&mut buf);
22554 let mut unstructured = Unstructured::new(&buf);
22555 Self::arbitrary(&mut unstructured).unwrap_or_default()
22556 }
22557}
22558impl Default for REQUEST_EVENT_DATA {
22559 fn default() -> Self {
22560 Self::DEFAULT.clone()
22561 }
22562}
22563impl MessageData for REQUEST_EVENT_DATA {
22564 type Message = MavMessage;
22565 const ID: u32 = 412u32;
22566 const NAME: &'static str = "REQUEST_EVENT";
22567 const EXTRA_CRC: u8 = 33u8;
22568 const ENCODED_LEN: usize = 6usize;
22569 fn deser(
22570 _version: MavlinkVersion,
22571 __input: &[u8],
22572 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22573 let avail_len = __input.len();
22574 let mut payload_buf = [0; Self::ENCODED_LEN];
22575 let mut buf = if avail_len < Self::ENCODED_LEN {
22576 payload_buf[0..avail_len].copy_from_slice(__input);
22577 Bytes::new(&payload_buf)
22578 } else {
22579 Bytes::new(__input)
22580 };
22581 let mut __struct = Self::default();
22582 __struct.first_sequence = buf.get_u16_le();
22583 __struct.last_sequence = buf.get_u16_le();
22584 __struct.target_system = buf.get_u8();
22585 __struct.target_component = buf.get_u8();
22586 Ok(__struct)
22587 }
22588 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22589 let mut __tmp = BytesMut::new(bytes);
22590 #[allow(clippy::absurd_extreme_comparisons)]
22591 #[allow(unused_comparisons)]
22592 if __tmp.remaining() < Self::ENCODED_LEN {
22593 panic!(
22594 "buffer is too small (need {} bytes, but got {})",
22595 Self::ENCODED_LEN,
22596 __tmp.remaining(),
22597 )
22598 }
22599 __tmp.put_u16_le(self.first_sequence);
22600 __tmp.put_u16_le(self.last_sequence);
22601 __tmp.put_u8(self.target_system);
22602 __tmp.put_u8(self.target_component);
22603 if matches!(version, MavlinkVersion::V2) {
22604 let len = __tmp.len();
22605 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22606 } else {
22607 __tmp.len()
22608 }
22609 }
22610}
22611#[doc = "id: 82"]
22612#[doc = "Sets a desired vehicle attitude. Used by an external controller to command the vehicle (manual controller or other system)."]
22613#[derive(Debug, Clone, PartialEq)]
22614#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22615#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22616pub struct SET_ATTITUDE_TARGET_DATA {
22617 #[doc = "Timestamp (time since system boot)."]
22618 pub time_boot_ms: u32,
22619 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0) from MAV_FRAME_LOCAL_NED to MAV_FRAME_BODY_FRD"]
22620 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22621 pub q: [f32; 4],
22622 #[doc = "Body roll rate"]
22623 pub body_roll_rate: f32,
22624 #[doc = "Body pitch rate"]
22625 pub body_pitch_rate: f32,
22626 #[doc = "Body yaw rate"]
22627 pub body_yaw_rate: f32,
22628 #[doc = "Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)"]
22629 pub thrust: f32,
22630 #[doc = "System ID"]
22631 pub target_system: u8,
22632 #[doc = "Component ID"]
22633 pub target_component: u8,
22634 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
22635 pub type_mask: AttitudeTargetTypemask,
22636 #[doc = "3D thrust setpoint in the body NED frame, normalized to -1 .. 1"]
22637 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
22638 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
22639 pub thrust_body: [f32; 3],
22640}
22641impl SET_ATTITUDE_TARGET_DATA {
22642 pub const ENCODED_LEN: usize = 51usize;
22643 pub const DEFAULT: Self = Self {
22644 time_boot_ms: 0_u32,
22645 q: [0.0_f32; 4usize],
22646 body_roll_rate: 0.0_f32,
22647 body_pitch_rate: 0.0_f32,
22648 body_yaw_rate: 0.0_f32,
22649 thrust: 0.0_f32,
22650 target_system: 0_u8,
22651 target_component: 0_u8,
22652 type_mask: AttitudeTargetTypemask::DEFAULT,
22653 thrust_body: [0.0_f32; 3usize],
22654 };
22655 #[cfg(feature = "arbitrary")]
22656 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22657 use arbitrary::{Arbitrary, Unstructured};
22658 let mut buf = [0u8; 1024];
22659 rng.fill_bytes(&mut buf);
22660 let mut unstructured = Unstructured::new(&buf);
22661 Self::arbitrary(&mut unstructured).unwrap_or_default()
22662 }
22663}
22664impl Default for SET_ATTITUDE_TARGET_DATA {
22665 fn default() -> Self {
22666 Self::DEFAULT.clone()
22667 }
22668}
22669impl MessageData for SET_ATTITUDE_TARGET_DATA {
22670 type Message = MavMessage;
22671 const ID: u32 = 82u32;
22672 const NAME: &'static str = "SET_ATTITUDE_TARGET";
22673 const EXTRA_CRC: u8 = 49u8;
22674 const ENCODED_LEN: usize = 51usize;
22675 fn deser(
22676 _version: MavlinkVersion,
22677 __input: &[u8],
22678 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22679 let avail_len = __input.len();
22680 let mut payload_buf = [0; Self::ENCODED_LEN];
22681 let mut buf = if avail_len < Self::ENCODED_LEN {
22682 payload_buf[0..avail_len].copy_from_slice(__input);
22683 Bytes::new(&payload_buf)
22684 } else {
22685 Bytes::new(__input)
22686 };
22687 let mut __struct = Self::default();
22688 __struct.time_boot_ms = buf.get_u32_le();
22689 for v in &mut __struct.q {
22690 let val = buf.get_f32_le();
22691 *v = val;
22692 }
22693 __struct.body_roll_rate = buf.get_f32_le();
22694 __struct.body_pitch_rate = buf.get_f32_le();
22695 __struct.body_yaw_rate = buf.get_f32_le();
22696 __struct.thrust = buf.get_f32_le();
22697 __struct.target_system = buf.get_u8();
22698 __struct.target_component = buf.get_u8();
22699 let tmp = buf.get_u8();
22700 __struct.type_mask = AttitudeTargetTypemask::from_bits(
22701 tmp & AttitudeTargetTypemask::all().bits(),
22702 )
22703 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22704 flag_type: "AttitudeTargetTypemask",
22705 value: tmp as u32,
22706 })?;
22707 for v in &mut __struct.thrust_body {
22708 let val = buf.get_f32_le();
22709 *v = val;
22710 }
22711 Ok(__struct)
22712 }
22713 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22714 let mut __tmp = BytesMut::new(bytes);
22715 #[allow(clippy::absurd_extreme_comparisons)]
22716 #[allow(unused_comparisons)]
22717 if __tmp.remaining() < Self::ENCODED_LEN {
22718 panic!(
22719 "buffer is too small (need {} bytes, but got {})",
22720 Self::ENCODED_LEN,
22721 __tmp.remaining(),
22722 )
22723 }
22724 __tmp.put_u32_le(self.time_boot_ms);
22725 for val in &self.q {
22726 __tmp.put_f32_le(*val);
22727 }
22728 __tmp.put_f32_le(self.body_roll_rate);
22729 __tmp.put_f32_le(self.body_pitch_rate);
22730 __tmp.put_f32_le(self.body_yaw_rate);
22731 __tmp.put_f32_le(self.thrust);
22732 __tmp.put_u8(self.target_system);
22733 __tmp.put_u8(self.target_component);
22734 __tmp.put_u8(self.type_mask.bits());
22735 for val in &self.thrust_body {
22736 __tmp.put_f32_le(*val);
22737 }
22738 if matches!(version, MavlinkVersion::V2) {
22739 let len = __tmp.len();
22740 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22741 } else {
22742 __tmp.len()
22743 }
22744 }
22745}
22746#[doc = "id: 84"]
22747#[doc = "Sets a desired vehicle position in a local north-east-down coordinate frame. Used by an external controller to command the vehicle (manual controller or other system)."]
22748#[derive(Debug, Clone, PartialEq)]
22749#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22750#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22751pub struct SET_POSITION_TARGET_LOCAL_NED_DATA {
22752 #[doc = "Timestamp (time since system boot)."]
22753 pub time_boot_ms: u32,
22754 #[doc = "X Position in NED frame"]
22755 pub x: f32,
22756 #[doc = "Y Position in NED frame"]
22757 pub y: f32,
22758 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
22759 pub z: f32,
22760 #[doc = "X velocity in NED frame"]
22761 pub vx: f32,
22762 #[doc = "Y velocity in NED frame"]
22763 pub vy: f32,
22764 #[doc = "Z velocity in NED frame"]
22765 pub vz: f32,
22766 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
22767 pub afx: f32,
22768 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
22769 pub afy: f32,
22770 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
22771 pub afz: f32,
22772 #[doc = "yaw setpoint"]
22773 pub yaw: f32,
22774 #[doc = "yaw rate setpoint"]
22775 pub yaw_rate: f32,
22776 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
22777 pub type_mask: PositionTargetTypemask,
22778 #[doc = "System ID"]
22779 pub target_system: u8,
22780 #[doc = "Component ID"]
22781 pub target_component: u8,
22782 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
22783 pub coordinate_frame: MavFrame,
22784}
22785impl SET_POSITION_TARGET_LOCAL_NED_DATA {
22786 pub const ENCODED_LEN: usize = 53usize;
22787 pub const DEFAULT: Self = Self {
22788 time_boot_ms: 0_u32,
22789 x: 0.0_f32,
22790 y: 0.0_f32,
22791 z: 0.0_f32,
22792 vx: 0.0_f32,
22793 vy: 0.0_f32,
22794 vz: 0.0_f32,
22795 afx: 0.0_f32,
22796 afy: 0.0_f32,
22797 afz: 0.0_f32,
22798 yaw: 0.0_f32,
22799 yaw_rate: 0.0_f32,
22800 type_mask: PositionTargetTypemask::DEFAULT,
22801 target_system: 0_u8,
22802 target_component: 0_u8,
22803 coordinate_frame: MavFrame::DEFAULT,
22804 };
22805 #[cfg(feature = "arbitrary")]
22806 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22807 use arbitrary::{Arbitrary, Unstructured};
22808 let mut buf = [0u8; 1024];
22809 rng.fill_bytes(&mut buf);
22810 let mut unstructured = Unstructured::new(&buf);
22811 Self::arbitrary(&mut unstructured).unwrap_or_default()
22812 }
22813}
22814impl Default for SET_POSITION_TARGET_LOCAL_NED_DATA {
22815 fn default() -> Self {
22816 Self::DEFAULT.clone()
22817 }
22818}
22819impl MessageData for SET_POSITION_TARGET_LOCAL_NED_DATA {
22820 type Message = MavMessage;
22821 const ID: u32 = 84u32;
22822 const NAME: &'static str = "SET_POSITION_TARGET_LOCAL_NED";
22823 const EXTRA_CRC: u8 = 143u8;
22824 const ENCODED_LEN: usize = 53usize;
22825 fn deser(
22826 _version: MavlinkVersion,
22827 __input: &[u8],
22828 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22829 let avail_len = __input.len();
22830 let mut payload_buf = [0; Self::ENCODED_LEN];
22831 let mut buf = if avail_len < Self::ENCODED_LEN {
22832 payload_buf[0..avail_len].copy_from_slice(__input);
22833 Bytes::new(&payload_buf)
22834 } else {
22835 Bytes::new(__input)
22836 };
22837 let mut __struct = Self::default();
22838 __struct.time_boot_ms = buf.get_u32_le();
22839 __struct.x = buf.get_f32_le();
22840 __struct.y = buf.get_f32_le();
22841 __struct.z = buf.get_f32_le();
22842 __struct.vx = buf.get_f32_le();
22843 __struct.vy = buf.get_f32_le();
22844 __struct.vz = buf.get_f32_le();
22845 __struct.afx = buf.get_f32_le();
22846 __struct.afy = buf.get_f32_le();
22847 __struct.afz = buf.get_f32_le();
22848 __struct.yaw = buf.get_f32_le();
22849 __struct.yaw_rate = buf.get_f32_le();
22850 let tmp = buf.get_u16_le();
22851 __struct.type_mask = PositionTargetTypemask::from_bits(
22852 tmp & PositionTargetTypemask::all().bits(),
22853 )
22854 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
22855 flag_type: "PositionTargetTypemask",
22856 value: tmp as u32,
22857 })?;
22858 __struct.target_system = buf.get_u8();
22859 __struct.target_component = buf.get_u8();
22860 let tmp = buf.get_u8();
22861 __struct.coordinate_frame =
22862 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
22863 enum_type: "MavFrame",
22864 value: tmp as u32,
22865 })?;
22866 Ok(__struct)
22867 }
22868 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22869 let mut __tmp = BytesMut::new(bytes);
22870 #[allow(clippy::absurd_extreme_comparisons)]
22871 #[allow(unused_comparisons)]
22872 if __tmp.remaining() < Self::ENCODED_LEN {
22873 panic!(
22874 "buffer is too small (need {} bytes, but got {})",
22875 Self::ENCODED_LEN,
22876 __tmp.remaining(),
22877 )
22878 }
22879 __tmp.put_u32_le(self.time_boot_ms);
22880 __tmp.put_f32_le(self.x);
22881 __tmp.put_f32_le(self.y);
22882 __tmp.put_f32_le(self.z);
22883 __tmp.put_f32_le(self.vx);
22884 __tmp.put_f32_le(self.vy);
22885 __tmp.put_f32_le(self.vz);
22886 __tmp.put_f32_le(self.afx);
22887 __tmp.put_f32_le(self.afy);
22888 __tmp.put_f32_le(self.afz);
22889 __tmp.put_f32_le(self.yaw);
22890 __tmp.put_f32_le(self.yaw_rate);
22891 __tmp.put_u16_le(self.type_mask.bits());
22892 __tmp.put_u8(self.target_system);
22893 __tmp.put_u8(self.target_component);
22894 __tmp.put_u8(self.coordinate_frame as u8);
22895 if matches!(version, MavlinkVersion::V2) {
22896 let len = __tmp.len();
22897 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22898 } else {
22899 __tmp.len()
22900 }
22901 }
22902}
22903#[doc = "id: 268"]
22904#[doc = "An ack for a LOGGING_DATA_ACKED message."]
22905#[derive(Debug, Clone, PartialEq)]
22906#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22907#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22908pub struct LOGGING_ACK_DATA {
22909 #[doc = "sequence number (must match the one in LOGGING_DATA_ACKED)"]
22910 pub sequence: u16,
22911 #[doc = "system ID of the target"]
22912 pub target_system: u8,
22913 #[doc = "component ID of the target"]
22914 pub target_component: u8,
22915}
22916impl LOGGING_ACK_DATA {
22917 pub const ENCODED_LEN: usize = 4usize;
22918 pub const DEFAULT: Self = Self {
22919 sequence: 0_u16,
22920 target_system: 0_u8,
22921 target_component: 0_u8,
22922 };
22923 #[cfg(feature = "arbitrary")]
22924 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
22925 use arbitrary::{Arbitrary, Unstructured};
22926 let mut buf = [0u8; 1024];
22927 rng.fill_bytes(&mut buf);
22928 let mut unstructured = Unstructured::new(&buf);
22929 Self::arbitrary(&mut unstructured).unwrap_or_default()
22930 }
22931}
22932impl Default for LOGGING_ACK_DATA {
22933 fn default() -> Self {
22934 Self::DEFAULT.clone()
22935 }
22936}
22937impl MessageData for LOGGING_ACK_DATA {
22938 type Message = MavMessage;
22939 const ID: u32 = 268u32;
22940 const NAME: &'static str = "LOGGING_ACK";
22941 const EXTRA_CRC: u8 = 14u8;
22942 const ENCODED_LEN: usize = 4usize;
22943 fn deser(
22944 _version: MavlinkVersion,
22945 __input: &[u8],
22946 ) -> Result<Self, ::mavlink_core::error::ParserError> {
22947 let avail_len = __input.len();
22948 let mut payload_buf = [0; Self::ENCODED_LEN];
22949 let mut buf = if avail_len < Self::ENCODED_LEN {
22950 payload_buf[0..avail_len].copy_from_slice(__input);
22951 Bytes::new(&payload_buf)
22952 } else {
22953 Bytes::new(__input)
22954 };
22955 let mut __struct = Self::default();
22956 __struct.sequence = buf.get_u16_le();
22957 __struct.target_system = buf.get_u8();
22958 __struct.target_component = buf.get_u8();
22959 Ok(__struct)
22960 }
22961 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
22962 let mut __tmp = BytesMut::new(bytes);
22963 #[allow(clippy::absurd_extreme_comparisons)]
22964 #[allow(unused_comparisons)]
22965 if __tmp.remaining() < Self::ENCODED_LEN {
22966 panic!(
22967 "buffer is too small (need {} bytes, but got {})",
22968 Self::ENCODED_LEN,
22969 __tmp.remaining(),
22970 )
22971 }
22972 __tmp.put_u16_le(self.sequence);
22973 __tmp.put_u8(self.target_system);
22974 __tmp.put_u8(self.target_component);
22975 if matches!(version, MavlinkVersion::V2) {
22976 let len = __tmp.len();
22977 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
22978 } else {
22979 __tmp.len()
22980 }
22981 }
22982}
22983#[doc = "id: 121"]
22984#[doc = "Erase all logs."]
22985#[derive(Debug, Clone, PartialEq)]
22986#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
22987#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
22988pub struct LOG_ERASE_DATA {
22989 #[doc = "System ID"]
22990 pub target_system: u8,
22991 #[doc = "Component ID"]
22992 pub target_component: u8,
22993}
22994impl LOG_ERASE_DATA {
22995 pub const ENCODED_LEN: usize = 2usize;
22996 pub const DEFAULT: Self = Self {
22997 target_system: 0_u8,
22998 target_component: 0_u8,
22999 };
23000 #[cfg(feature = "arbitrary")]
23001 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23002 use arbitrary::{Arbitrary, Unstructured};
23003 let mut buf = [0u8; 1024];
23004 rng.fill_bytes(&mut buf);
23005 let mut unstructured = Unstructured::new(&buf);
23006 Self::arbitrary(&mut unstructured).unwrap_or_default()
23007 }
23008}
23009impl Default for LOG_ERASE_DATA {
23010 fn default() -> Self {
23011 Self::DEFAULT.clone()
23012 }
23013}
23014impl MessageData for LOG_ERASE_DATA {
23015 type Message = MavMessage;
23016 const ID: u32 = 121u32;
23017 const NAME: &'static str = "LOG_ERASE";
23018 const EXTRA_CRC: u8 = 237u8;
23019 const ENCODED_LEN: usize = 2usize;
23020 fn deser(
23021 _version: MavlinkVersion,
23022 __input: &[u8],
23023 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23024 let avail_len = __input.len();
23025 let mut payload_buf = [0; Self::ENCODED_LEN];
23026 let mut buf = if avail_len < Self::ENCODED_LEN {
23027 payload_buf[0..avail_len].copy_from_slice(__input);
23028 Bytes::new(&payload_buf)
23029 } else {
23030 Bytes::new(__input)
23031 };
23032 let mut __struct = Self::default();
23033 __struct.target_system = buf.get_u8();
23034 __struct.target_component = buf.get_u8();
23035 Ok(__struct)
23036 }
23037 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23038 let mut __tmp = BytesMut::new(bytes);
23039 #[allow(clippy::absurd_extreme_comparisons)]
23040 #[allow(unused_comparisons)]
23041 if __tmp.remaining() < Self::ENCODED_LEN {
23042 panic!(
23043 "buffer is too small (need {} bytes, but got {})",
23044 Self::ENCODED_LEN,
23045 __tmp.remaining(),
23046 )
23047 }
23048 __tmp.put_u8(self.target_system);
23049 __tmp.put_u8(self.target_component);
23050 if matches!(version, MavlinkVersion::V2) {
23051 let len = __tmp.len();
23052 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23053 } else {
23054 __tmp.len()
23055 }
23056 }
23057}
23058#[doc = "id: 12901"]
23059#[doc = "Data for filling the OpenDroneID Location message. The float data types are 32-bit IEEE 754. The Location message provides the location, altitude, direction and speed of the aircraft."]
23060#[derive(Debug, Clone, PartialEq)]
23061#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23062#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23063pub struct OPEN_DRONE_ID_LOCATION_DATA {
23064 #[doc = "Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
23065 pub latitude: i32,
23066 #[doc = "Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon)."]
23067 pub longitude: i32,
23068 #[doc = "The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m."]
23069 pub altitude_barometric: f32,
23070 #[doc = "The geodetic altitude as defined by WGS84. If unknown: -1000 m."]
23071 pub altitude_geodetic: f32,
23072 #[doc = "The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m."]
23073 pub height: f32,
23074 #[doc = "Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000. If unknown: 0xFFFF."]
23075 pub timestamp: f32,
23076 #[doc = "Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees."]
23077 pub direction: u16,
23078 #[doc = "Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s."]
23079 pub speed_horizontal: u16,
23080 #[doc = "The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s."]
23081 pub speed_vertical: i16,
23082 #[doc = "System ID (0 for broadcast)."]
23083 pub target_system: u8,
23084 #[doc = "Component ID (0 for broadcast)."]
23085 pub target_component: u8,
23086 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
23087 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23088 pub id_or_mac: [u8; 20],
23089 #[doc = "Indicates whether the unmanned aircraft is on the ground or in the air."]
23090 pub status: MavOdidStatus,
23091 #[doc = "Indicates the reference point for the height field."]
23092 pub height_reference: MavOdidHeightRef,
23093 #[doc = "The accuracy of the horizontal position."]
23094 pub horizontal_accuracy: MavOdidHorAcc,
23095 #[doc = "The accuracy of the vertical position."]
23096 pub vertical_accuracy: MavOdidVerAcc,
23097 #[doc = "The accuracy of the barometric altitude."]
23098 pub barometer_accuracy: MavOdidVerAcc,
23099 #[doc = "The accuracy of the horizontal and vertical speed."]
23100 pub speed_accuracy: MavOdidSpeedAcc,
23101 #[doc = "The accuracy of the timestamps."]
23102 pub timestamp_accuracy: MavOdidTimeAcc,
23103}
23104impl OPEN_DRONE_ID_LOCATION_DATA {
23105 pub const ENCODED_LEN: usize = 59usize;
23106 pub const DEFAULT: Self = Self {
23107 latitude: 0_i32,
23108 longitude: 0_i32,
23109 altitude_barometric: 0.0_f32,
23110 altitude_geodetic: 0.0_f32,
23111 height: 0.0_f32,
23112 timestamp: 0.0_f32,
23113 direction: 0_u16,
23114 speed_horizontal: 0_u16,
23115 speed_vertical: 0_i16,
23116 target_system: 0_u8,
23117 target_component: 0_u8,
23118 id_or_mac: [0_u8; 20usize],
23119 status: MavOdidStatus::DEFAULT,
23120 height_reference: MavOdidHeightRef::DEFAULT,
23121 horizontal_accuracy: MavOdidHorAcc::DEFAULT,
23122 vertical_accuracy: MavOdidVerAcc::DEFAULT,
23123 barometer_accuracy: MavOdidVerAcc::DEFAULT,
23124 speed_accuracy: MavOdidSpeedAcc::DEFAULT,
23125 timestamp_accuracy: MavOdidTimeAcc::DEFAULT,
23126 };
23127 #[cfg(feature = "arbitrary")]
23128 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23129 use arbitrary::{Arbitrary, Unstructured};
23130 let mut buf = [0u8; 1024];
23131 rng.fill_bytes(&mut buf);
23132 let mut unstructured = Unstructured::new(&buf);
23133 Self::arbitrary(&mut unstructured).unwrap_or_default()
23134 }
23135}
23136impl Default for OPEN_DRONE_ID_LOCATION_DATA {
23137 fn default() -> Self {
23138 Self::DEFAULT.clone()
23139 }
23140}
23141impl MessageData for OPEN_DRONE_ID_LOCATION_DATA {
23142 type Message = MavMessage;
23143 const ID: u32 = 12901u32;
23144 const NAME: &'static str = "OPEN_DRONE_ID_LOCATION";
23145 const EXTRA_CRC: u8 = 254u8;
23146 const ENCODED_LEN: usize = 59usize;
23147 fn deser(
23148 _version: MavlinkVersion,
23149 __input: &[u8],
23150 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23151 let avail_len = __input.len();
23152 let mut payload_buf = [0; Self::ENCODED_LEN];
23153 let mut buf = if avail_len < Self::ENCODED_LEN {
23154 payload_buf[0..avail_len].copy_from_slice(__input);
23155 Bytes::new(&payload_buf)
23156 } else {
23157 Bytes::new(__input)
23158 };
23159 let mut __struct = Self::default();
23160 __struct.latitude = buf.get_i32_le();
23161 __struct.longitude = buf.get_i32_le();
23162 __struct.altitude_barometric = buf.get_f32_le();
23163 __struct.altitude_geodetic = buf.get_f32_le();
23164 __struct.height = buf.get_f32_le();
23165 __struct.timestamp = buf.get_f32_le();
23166 __struct.direction = buf.get_u16_le();
23167 __struct.speed_horizontal = buf.get_u16_le();
23168 __struct.speed_vertical = buf.get_i16_le();
23169 __struct.target_system = buf.get_u8();
23170 __struct.target_component = buf.get_u8();
23171 for v in &mut __struct.id_or_mac {
23172 let val = buf.get_u8();
23173 *v = val;
23174 }
23175 let tmp = buf.get_u8();
23176 __struct.status =
23177 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23178 enum_type: "MavOdidStatus",
23179 value: tmp as u32,
23180 })?;
23181 let tmp = buf.get_u8();
23182 __struct.height_reference =
23183 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23184 enum_type: "MavOdidHeightRef",
23185 value: tmp as u32,
23186 })?;
23187 let tmp = buf.get_u8();
23188 __struct.horizontal_accuracy =
23189 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23190 enum_type: "MavOdidHorAcc",
23191 value: tmp as u32,
23192 })?;
23193 let tmp = buf.get_u8();
23194 __struct.vertical_accuracy =
23195 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23196 enum_type: "MavOdidVerAcc",
23197 value: tmp as u32,
23198 })?;
23199 let tmp = buf.get_u8();
23200 __struct.barometer_accuracy =
23201 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23202 enum_type: "MavOdidVerAcc",
23203 value: tmp as u32,
23204 })?;
23205 let tmp = buf.get_u8();
23206 __struct.speed_accuracy =
23207 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23208 enum_type: "MavOdidSpeedAcc",
23209 value: tmp as u32,
23210 })?;
23211 let tmp = buf.get_u8();
23212 __struct.timestamp_accuracy =
23213 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23214 enum_type: "MavOdidTimeAcc",
23215 value: tmp as u32,
23216 })?;
23217 Ok(__struct)
23218 }
23219 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23220 let mut __tmp = BytesMut::new(bytes);
23221 #[allow(clippy::absurd_extreme_comparisons)]
23222 #[allow(unused_comparisons)]
23223 if __tmp.remaining() < Self::ENCODED_LEN {
23224 panic!(
23225 "buffer is too small (need {} bytes, but got {})",
23226 Self::ENCODED_LEN,
23227 __tmp.remaining(),
23228 )
23229 }
23230 __tmp.put_i32_le(self.latitude);
23231 __tmp.put_i32_le(self.longitude);
23232 __tmp.put_f32_le(self.altitude_barometric);
23233 __tmp.put_f32_le(self.altitude_geodetic);
23234 __tmp.put_f32_le(self.height);
23235 __tmp.put_f32_le(self.timestamp);
23236 __tmp.put_u16_le(self.direction);
23237 __tmp.put_u16_le(self.speed_horizontal);
23238 __tmp.put_i16_le(self.speed_vertical);
23239 __tmp.put_u8(self.target_system);
23240 __tmp.put_u8(self.target_component);
23241 for val in &self.id_or_mac {
23242 __tmp.put_u8(*val);
23243 }
23244 __tmp.put_u8(self.status as u8);
23245 __tmp.put_u8(self.height_reference as u8);
23246 __tmp.put_u8(self.horizontal_accuracy as u8);
23247 __tmp.put_u8(self.vertical_accuracy as u8);
23248 __tmp.put_u8(self.barometer_accuracy as u8);
23249 __tmp.put_u8(self.speed_accuracy as u8);
23250 __tmp.put_u8(self.timestamp_accuracy as u8);
23251 if matches!(version, MavlinkVersion::V2) {
23252 let len = __tmp.len();
23253 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23254 } else {
23255 __tmp.len()
23256 }
23257 }
23258}
23259#[doc = "id: 10001"]
23260#[doc = "Static data to configure the ADS-B transponder (send within 10 sec of a POR and every 10 sec thereafter)."]
23261#[derive(Debug, Clone, PartialEq)]
23262#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23263#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23264pub struct UAVIONIX_ADSB_OUT_CFG_DATA {
23265 #[doc = "Vehicle address (24 bit)"]
23266 pub ICAO: u32,
23267 #[doc = "Aircraft stall speed in cm/s"]
23268 pub stallSpeed: u16,
23269 #[doc = "Vehicle identifier (8 characters, null terminated, valid characters are A-Z, 0-9, \" \" only)"]
23270 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23271 pub callsign: [u8; 9],
23272 #[doc = "Transmitting vehicle type. See ADSB_EMITTER_TYPE enum"]
23273 pub emitterType: AdsbEmitterType,
23274 #[doc = "Aircraft length and width encoding (table 2-35 of DO-282B)"]
23275 pub aircraftSize: UavionixAdsbOutCfgAircraftSize,
23276 #[doc = "GPS antenna lateral offset (table 2-36 of DO-282B)"]
23277 pub gpsOffsetLat: UavionixAdsbOutCfgGpsOffsetLat,
23278 #[doc = "GPS antenna longitudinal offset from nose [if non-zero, take position (in meters) divide by 2 and add one] (table 2-37 DO-282B)"]
23279 pub gpsOffsetLon: UavionixAdsbOutCfgGpsOffsetLon,
23280 #[doc = "ADS-B transponder reciever and transmit enable flags"]
23281 pub rfSelect: UavionixAdsbOutRfSelect,
23282}
23283impl UAVIONIX_ADSB_OUT_CFG_DATA {
23284 pub const ENCODED_LEN: usize = 20usize;
23285 pub const DEFAULT: Self = Self {
23286 ICAO: 0_u32,
23287 stallSpeed: 0_u16,
23288 callsign: [0_u8; 9usize],
23289 emitterType: AdsbEmitterType::DEFAULT,
23290 aircraftSize: UavionixAdsbOutCfgAircraftSize::DEFAULT,
23291 gpsOffsetLat: UavionixAdsbOutCfgGpsOffsetLat::DEFAULT,
23292 gpsOffsetLon: UavionixAdsbOutCfgGpsOffsetLon::DEFAULT,
23293 rfSelect: UavionixAdsbOutRfSelect::DEFAULT,
23294 };
23295 #[cfg(feature = "arbitrary")]
23296 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23297 use arbitrary::{Arbitrary, Unstructured};
23298 let mut buf = [0u8; 1024];
23299 rng.fill_bytes(&mut buf);
23300 let mut unstructured = Unstructured::new(&buf);
23301 Self::arbitrary(&mut unstructured).unwrap_or_default()
23302 }
23303}
23304impl Default for UAVIONIX_ADSB_OUT_CFG_DATA {
23305 fn default() -> Self {
23306 Self::DEFAULT.clone()
23307 }
23308}
23309impl MessageData for UAVIONIX_ADSB_OUT_CFG_DATA {
23310 type Message = MavMessage;
23311 const ID: u32 = 10001u32;
23312 const NAME: &'static str = "UAVIONIX_ADSB_OUT_CFG";
23313 const EXTRA_CRC: u8 = 209u8;
23314 const ENCODED_LEN: usize = 20usize;
23315 fn deser(
23316 _version: MavlinkVersion,
23317 __input: &[u8],
23318 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23319 let avail_len = __input.len();
23320 let mut payload_buf = [0; Self::ENCODED_LEN];
23321 let mut buf = if avail_len < Self::ENCODED_LEN {
23322 payload_buf[0..avail_len].copy_from_slice(__input);
23323 Bytes::new(&payload_buf)
23324 } else {
23325 Bytes::new(__input)
23326 };
23327 let mut __struct = Self::default();
23328 __struct.ICAO = buf.get_u32_le();
23329 __struct.stallSpeed = buf.get_u16_le();
23330 for v in &mut __struct.callsign {
23331 let val = buf.get_u8();
23332 *v = val;
23333 }
23334 let tmp = buf.get_u8();
23335 __struct.emitterType =
23336 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23337 enum_type: "AdsbEmitterType",
23338 value: tmp as u32,
23339 })?;
23340 let tmp = buf.get_u8();
23341 __struct.aircraftSize =
23342 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23343 enum_type: "UavionixAdsbOutCfgAircraftSize",
23344 value: tmp as u32,
23345 })?;
23346 let tmp = buf.get_u8();
23347 __struct.gpsOffsetLat =
23348 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23349 enum_type: "UavionixAdsbOutCfgGpsOffsetLat",
23350 value: tmp as u32,
23351 })?;
23352 let tmp = buf.get_u8();
23353 __struct.gpsOffsetLon =
23354 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23355 enum_type: "UavionixAdsbOutCfgGpsOffsetLon",
23356 value: tmp as u32,
23357 })?;
23358 let tmp = buf.get_u8();
23359 __struct.rfSelect = UavionixAdsbOutRfSelect::from_bits(
23360 tmp & UavionixAdsbOutRfSelect::all().bits(),
23361 )
23362 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
23363 flag_type: "UavionixAdsbOutRfSelect",
23364 value: tmp as u32,
23365 })?;
23366 Ok(__struct)
23367 }
23368 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23369 let mut __tmp = BytesMut::new(bytes);
23370 #[allow(clippy::absurd_extreme_comparisons)]
23371 #[allow(unused_comparisons)]
23372 if __tmp.remaining() < Self::ENCODED_LEN {
23373 panic!(
23374 "buffer is too small (need {} bytes, but got {})",
23375 Self::ENCODED_LEN,
23376 __tmp.remaining(),
23377 )
23378 }
23379 __tmp.put_u32_le(self.ICAO);
23380 __tmp.put_u16_le(self.stallSpeed);
23381 for val in &self.callsign {
23382 __tmp.put_u8(*val);
23383 }
23384 __tmp.put_u8(self.emitterType as u8);
23385 __tmp.put_u8(self.aircraftSize as u8);
23386 __tmp.put_u8(self.gpsOffsetLat as u8);
23387 __tmp.put_u8(self.gpsOffsetLon as u8);
23388 __tmp.put_u8(self.rfSelect.bits());
23389 if matches!(version, MavlinkVersion::V2) {
23390 let len = __tmp.len();
23391 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23392 } else {
23393 __tmp.len()
23394 }
23395 }
23396}
23397#[doc = "id: 333"]
23398#[doc = "Describe a trajectory using an array of up-to 5 bezier control points in the local frame (MAV_FRAME_LOCAL_NED)."]
23399#[derive(Debug, Clone, PartialEq)]
23400#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23401#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23402pub struct TRAJECTORY_REPRESENTATION_BEZIER_DATA {
23403 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
23404 pub time_usec: u64,
23405 #[doc = "X-coordinate of bezier control points. Set to NaN if not being used"]
23406 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23407 pub pos_x: [f32; 5],
23408 #[doc = "Y-coordinate of bezier control points. Set to NaN if not being used"]
23409 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23410 pub pos_y: [f32; 5],
23411 #[doc = "Z-coordinate of bezier control points. Set to NaN if not being used"]
23412 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23413 pub pos_z: [f32; 5],
23414 #[doc = "Bezier time horizon. Set to NaN if velocity/acceleration should not be incorporated"]
23415 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23416 pub delta: [f32; 5],
23417 #[doc = "Yaw. Set to NaN for unchanged"]
23418 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23419 pub pos_yaw: [f32; 5],
23420 #[doc = "Number of valid control points (up-to 5 points are possible)"]
23421 pub valid_points: u8,
23422}
23423impl TRAJECTORY_REPRESENTATION_BEZIER_DATA {
23424 pub const ENCODED_LEN: usize = 109usize;
23425 pub const DEFAULT: Self = Self {
23426 time_usec: 0_u64,
23427 pos_x: [0.0_f32; 5usize],
23428 pos_y: [0.0_f32; 5usize],
23429 pos_z: [0.0_f32; 5usize],
23430 delta: [0.0_f32; 5usize],
23431 pos_yaw: [0.0_f32; 5usize],
23432 valid_points: 0_u8,
23433 };
23434 #[cfg(feature = "arbitrary")]
23435 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23436 use arbitrary::{Arbitrary, Unstructured};
23437 let mut buf = [0u8; 1024];
23438 rng.fill_bytes(&mut buf);
23439 let mut unstructured = Unstructured::new(&buf);
23440 Self::arbitrary(&mut unstructured).unwrap_or_default()
23441 }
23442}
23443impl Default for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
23444 fn default() -> Self {
23445 Self::DEFAULT.clone()
23446 }
23447}
23448impl MessageData for TRAJECTORY_REPRESENTATION_BEZIER_DATA {
23449 type Message = MavMessage;
23450 const ID: u32 = 333u32;
23451 const NAME: &'static str = "TRAJECTORY_REPRESENTATION_BEZIER";
23452 const EXTRA_CRC: u8 = 231u8;
23453 const ENCODED_LEN: usize = 109usize;
23454 fn deser(
23455 _version: MavlinkVersion,
23456 __input: &[u8],
23457 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23458 let avail_len = __input.len();
23459 let mut payload_buf = [0; Self::ENCODED_LEN];
23460 let mut buf = if avail_len < Self::ENCODED_LEN {
23461 payload_buf[0..avail_len].copy_from_slice(__input);
23462 Bytes::new(&payload_buf)
23463 } else {
23464 Bytes::new(__input)
23465 };
23466 let mut __struct = Self::default();
23467 __struct.time_usec = buf.get_u64_le();
23468 for v in &mut __struct.pos_x {
23469 let val = buf.get_f32_le();
23470 *v = val;
23471 }
23472 for v in &mut __struct.pos_y {
23473 let val = buf.get_f32_le();
23474 *v = val;
23475 }
23476 for v in &mut __struct.pos_z {
23477 let val = buf.get_f32_le();
23478 *v = val;
23479 }
23480 for v in &mut __struct.delta {
23481 let val = buf.get_f32_le();
23482 *v = val;
23483 }
23484 for v in &mut __struct.pos_yaw {
23485 let val = buf.get_f32_le();
23486 *v = val;
23487 }
23488 __struct.valid_points = buf.get_u8();
23489 Ok(__struct)
23490 }
23491 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23492 let mut __tmp = BytesMut::new(bytes);
23493 #[allow(clippy::absurd_extreme_comparisons)]
23494 #[allow(unused_comparisons)]
23495 if __tmp.remaining() < Self::ENCODED_LEN {
23496 panic!(
23497 "buffer is too small (need {} bytes, but got {})",
23498 Self::ENCODED_LEN,
23499 __tmp.remaining(),
23500 )
23501 }
23502 __tmp.put_u64_le(self.time_usec);
23503 for val in &self.pos_x {
23504 __tmp.put_f32_le(*val);
23505 }
23506 for val in &self.pos_y {
23507 __tmp.put_f32_le(*val);
23508 }
23509 for val in &self.pos_z {
23510 __tmp.put_f32_le(*val);
23511 }
23512 for val in &self.delta {
23513 __tmp.put_f32_le(*val);
23514 }
23515 for val in &self.pos_yaw {
23516 __tmp.put_f32_le(*val);
23517 }
23518 __tmp.put_u8(self.valid_points);
23519 if matches!(version, MavlinkVersion::V2) {
23520 let len = __tmp.len();
23521 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23522 } else {
23523 __tmp.len()
23524 }
23525 }
23526}
23527#[doc = "id: 108"]
23528#[doc = "Status of simulation environment, if used."]
23529#[derive(Debug, Clone, PartialEq)]
23530#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23531#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23532pub struct SIM_STATE_DATA {
23533 #[doc = "True attitude quaternion component 1, w (1 in null-rotation)"]
23534 pub q1: f32,
23535 #[doc = "True attitude quaternion component 2, x (0 in null-rotation)"]
23536 pub q2: f32,
23537 #[doc = "True attitude quaternion component 3, y (0 in null-rotation)"]
23538 pub q3: f32,
23539 #[doc = "True attitude quaternion component 4, z (0 in null-rotation)"]
23540 pub q4: f32,
23541 #[doc = "Attitude roll expressed as Euler angles, not recommended except for human-readable outputs"]
23542 pub roll: f32,
23543 #[doc = "Attitude pitch expressed as Euler angles, not recommended except for human-readable outputs"]
23544 pub pitch: f32,
23545 #[doc = "Attitude yaw expressed as Euler angles, not recommended except for human-readable outputs"]
23546 pub yaw: f32,
23547 #[doc = "X acceleration"]
23548 pub xacc: f32,
23549 #[doc = "Y acceleration"]
23550 pub yacc: f32,
23551 #[doc = "Z acceleration"]
23552 pub zacc: f32,
23553 #[doc = "Angular speed around X axis"]
23554 pub xgyro: f32,
23555 #[doc = "Angular speed around Y axis"]
23556 pub ygyro: f32,
23557 #[doc = "Angular speed around Z axis"]
23558 pub zgyro: f32,
23559 #[doc = "Latitude (lower precision). Both this and the lat_int field should be set."]
23560 pub lat: f32,
23561 #[doc = "Longitude (lower precision). Both this and the lon_int field should be set."]
23562 pub lon: f32,
23563 #[doc = "Altitude"]
23564 pub alt: f32,
23565 #[doc = "Horizontal position standard deviation"]
23566 pub std_dev_horz: f32,
23567 #[doc = "Vertical position standard deviation"]
23568 pub std_dev_vert: f32,
23569 #[doc = "True velocity in north direction in earth-fixed NED frame"]
23570 pub vn: f32,
23571 #[doc = "True velocity in east direction in earth-fixed NED frame"]
23572 pub ve: f32,
23573 #[doc = "True velocity in down direction in earth-fixed NED frame"]
23574 pub vd: f32,
23575 #[doc = "Latitude (higher precision). If 0, recipients should use the lat field value (otherwise this field is preferred)."]
23576 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23577 pub lat_int: i32,
23578 #[doc = "Longitude (higher precision). If 0, recipients should use the lon field value (otherwise this field is preferred)."]
23579 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23580 pub lon_int: i32,
23581}
23582impl SIM_STATE_DATA {
23583 pub const ENCODED_LEN: usize = 92usize;
23584 pub const DEFAULT: Self = Self {
23585 q1: 0.0_f32,
23586 q2: 0.0_f32,
23587 q3: 0.0_f32,
23588 q4: 0.0_f32,
23589 roll: 0.0_f32,
23590 pitch: 0.0_f32,
23591 yaw: 0.0_f32,
23592 xacc: 0.0_f32,
23593 yacc: 0.0_f32,
23594 zacc: 0.0_f32,
23595 xgyro: 0.0_f32,
23596 ygyro: 0.0_f32,
23597 zgyro: 0.0_f32,
23598 lat: 0.0_f32,
23599 lon: 0.0_f32,
23600 alt: 0.0_f32,
23601 std_dev_horz: 0.0_f32,
23602 std_dev_vert: 0.0_f32,
23603 vn: 0.0_f32,
23604 ve: 0.0_f32,
23605 vd: 0.0_f32,
23606 lat_int: 0_i32,
23607 lon_int: 0_i32,
23608 };
23609 #[cfg(feature = "arbitrary")]
23610 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23611 use arbitrary::{Arbitrary, Unstructured};
23612 let mut buf = [0u8; 1024];
23613 rng.fill_bytes(&mut buf);
23614 let mut unstructured = Unstructured::new(&buf);
23615 Self::arbitrary(&mut unstructured).unwrap_or_default()
23616 }
23617}
23618impl Default for SIM_STATE_DATA {
23619 fn default() -> Self {
23620 Self::DEFAULT.clone()
23621 }
23622}
23623impl MessageData for SIM_STATE_DATA {
23624 type Message = MavMessage;
23625 const ID: u32 = 108u32;
23626 const NAME: &'static str = "SIM_STATE";
23627 const EXTRA_CRC: u8 = 32u8;
23628 const ENCODED_LEN: usize = 92usize;
23629 fn deser(
23630 _version: MavlinkVersion,
23631 __input: &[u8],
23632 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23633 let avail_len = __input.len();
23634 let mut payload_buf = [0; Self::ENCODED_LEN];
23635 let mut buf = if avail_len < Self::ENCODED_LEN {
23636 payload_buf[0..avail_len].copy_from_slice(__input);
23637 Bytes::new(&payload_buf)
23638 } else {
23639 Bytes::new(__input)
23640 };
23641 let mut __struct = Self::default();
23642 __struct.q1 = buf.get_f32_le();
23643 __struct.q2 = buf.get_f32_le();
23644 __struct.q3 = buf.get_f32_le();
23645 __struct.q4 = buf.get_f32_le();
23646 __struct.roll = buf.get_f32_le();
23647 __struct.pitch = buf.get_f32_le();
23648 __struct.yaw = buf.get_f32_le();
23649 __struct.xacc = buf.get_f32_le();
23650 __struct.yacc = buf.get_f32_le();
23651 __struct.zacc = buf.get_f32_le();
23652 __struct.xgyro = buf.get_f32_le();
23653 __struct.ygyro = buf.get_f32_le();
23654 __struct.zgyro = buf.get_f32_le();
23655 __struct.lat = buf.get_f32_le();
23656 __struct.lon = buf.get_f32_le();
23657 __struct.alt = buf.get_f32_le();
23658 __struct.std_dev_horz = buf.get_f32_le();
23659 __struct.std_dev_vert = buf.get_f32_le();
23660 __struct.vn = buf.get_f32_le();
23661 __struct.ve = buf.get_f32_le();
23662 __struct.vd = buf.get_f32_le();
23663 __struct.lat_int = buf.get_i32_le();
23664 __struct.lon_int = buf.get_i32_le();
23665 Ok(__struct)
23666 }
23667 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23668 let mut __tmp = BytesMut::new(bytes);
23669 #[allow(clippy::absurd_extreme_comparisons)]
23670 #[allow(unused_comparisons)]
23671 if __tmp.remaining() < Self::ENCODED_LEN {
23672 panic!(
23673 "buffer is too small (need {} bytes, but got {})",
23674 Self::ENCODED_LEN,
23675 __tmp.remaining(),
23676 )
23677 }
23678 __tmp.put_f32_le(self.q1);
23679 __tmp.put_f32_le(self.q2);
23680 __tmp.put_f32_le(self.q3);
23681 __tmp.put_f32_le(self.q4);
23682 __tmp.put_f32_le(self.roll);
23683 __tmp.put_f32_le(self.pitch);
23684 __tmp.put_f32_le(self.yaw);
23685 __tmp.put_f32_le(self.xacc);
23686 __tmp.put_f32_le(self.yacc);
23687 __tmp.put_f32_le(self.zacc);
23688 __tmp.put_f32_le(self.xgyro);
23689 __tmp.put_f32_le(self.ygyro);
23690 __tmp.put_f32_le(self.zgyro);
23691 __tmp.put_f32_le(self.lat);
23692 __tmp.put_f32_le(self.lon);
23693 __tmp.put_f32_le(self.alt);
23694 __tmp.put_f32_le(self.std_dev_horz);
23695 __tmp.put_f32_le(self.std_dev_vert);
23696 __tmp.put_f32_le(self.vn);
23697 __tmp.put_f32_le(self.ve);
23698 __tmp.put_f32_le(self.vd);
23699 __tmp.put_i32_le(self.lat_int);
23700 __tmp.put_i32_le(self.lon_int);
23701 if matches!(version, MavlinkVersion::V2) {
23702 let len = __tmp.len();
23703 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23704 } else {
23705 __tmp.len()
23706 }
23707 }
23708}
23709#[doc = "id: 331"]
23710#[doc = "Odometry message to communicate odometry information with an external interface. Fits ROS REP 147 standard for aerial vehicles (<http://www.ros.org/reps/rep-0147.html>)."]
23711#[derive(Debug, Clone, PartialEq)]
23712#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23713#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23714pub struct ODOMETRY_DATA {
23715 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
23716 pub time_usec: u64,
23717 #[doc = "X Position"]
23718 pub x: f32,
23719 #[doc = "Y Position"]
23720 pub y: f32,
23721 #[doc = "Z Position"]
23722 pub z: f32,
23723 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
23724 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23725 pub q: [f32; 4],
23726 #[doc = "X linear speed"]
23727 pub vx: f32,
23728 #[doc = "Y linear speed"]
23729 pub vy: f32,
23730 #[doc = "Z linear speed"]
23731 pub vz: f32,
23732 #[doc = "Roll angular speed"]
23733 pub rollspeed: f32,
23734 #[doc = "Pitch angular speed"]
23735 pub pitchspeed: f32,
23736 #[doc = "Yaw angular speed"]
23737 pub yawspeed: f32,
23738 #[doc = "Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
23739 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23740 pub pose_covariance: [f32; 21],
23741 #[doc = "Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
23742 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23743 pub velocity_covariance: [f32; 21],
23744 #[doc = "Coordinate frame of reference for the pose data."]
23745 pub frame_id: MavFrame,
23746 #[doc = "Coordinate frame of reference for the velocity in free space (twist) data."]
23747 pub child_frame_id: MavFrame,
23748 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
23749 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23750 pub reset_counter: u8,
23751 #[doc = "Type of estimator that is providing the odometry."]
23752 #[cfg_attr(feature = "serde", serde(default))]
23753 pub estimator_type: MavEstimatorType,
23754 #[doc = "Optional odometry quality metric as a percentage. -1 = odometry has failed, 0 = unknown/unset quality, 1 = worst quality, 100 = best quality"]
23755 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23756 pub quality: i8,
23757}
23758impl ODOMETRY_DATA {
23759 pub const ENCODED_LEN: usize = 233usize;
23760 pub const DEFAULT: Self = Self {
23761 time_usec: 0_u64,
23762 x: 0.0_f32,
23763 y: 0.0_f32,
23764 z: 0.0_f32,
23765 q: [0.0_f32; 4usize],
23766 vx: 0.0_f32,
23767 vy: 0.0_f32,
23768 vz: 0.0_f32,
23769 rollspeed: 0.0_f32,
23770 pitchspeed: 0.0_f32,
23771 yawspeed: 0.0_f32,
23772 pose_covariance: [0.0_f32; 21usize],
23773 velocity_covariance: [0.0_f32; 21usize],
23774 frame_id: MavFrame::DEFAULT,
23775 child_frame_id: MavFrame::DEFAULT,
23776 reset_counter: 0_u8,
23777 estimator_type: MavEstimatorType::DEFAULT,
23778 quality: 0_i8,
23779 };
23780 #[cfg(feature = "arbitrary")]
23781 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23782 use arbitrary::{Arbitrary, Unstructured};
23783 let mut buf = [0u8; 1024];
23784 rng.fill_bytes(&mut buf);
23785 let mut unstructured = Unstructured::new(&buf);
23786 Self::arbitrary(&mut unstructured).unwrap_or_default()
23787 }
23788}
23789impl Default for ODOMETRY_DATA {
23790 fn default() -> Self {
23791 Self::DEFAULT.clone()
23792 }
23793}
23794impl MessageData for ODOMETRY_DATA {
23795 type Message = MavMessage;
23796 const ID: u32 = 331u32;
23797 const NAME: &'static str = "ODOMETRY";
23798 const EXTRA_CRC: u8 = 91u8;
23799 const ENCODED_LEN: usize = 233usize;
23800 fn deser(
23801 _version: MavlinkVersion,
23802 __input: &[u8],
23803 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23804 let avail_len = __input.len();
23805 let mut payload_buf = [0; Self::ENCODED_LEN];
23806 let mut buf = if avail_len < Self::ENCODED_LEN {
23807 payload_buf[0..avail_len].copy_from_slice(__input);
23808 Bytes::new(&payload_buf)
23809 } else {
23810 Bytes::new(__input)
23811 };
23812 let mut __struct = Self::default();
23813 __struct.time_usec = buf.get_u64_le();
23814 __struct.x = buf.get_f32_le();
23815 __struct.y = buf.get_f32_le();
23816 __struct.z = buf.get_f32_le();
23817 for v in &mut __struct.q {
23818 let val = buf.get_f32_le();
23819 *v = val;
23820 }
23821 __struct.vx = buf.get_f32_le();
23822 __struct.vy = buf.get_f32_le();
23823 __struct.vz = buf.get_f32_le();
23824 __struct.rollspeed = buf.get_f32_le();
23825 __struct.pitchspeed = buf.get_f32_le();
23826 __struct.yawspeed = buf.get_f32_le();
23827 for v in &mut __struct.pose_covariance {
23828 let val = buf.get_f32_le();
23829 *v = val;
23830 }
23831 for v in &mut __struct.velocity_covariance {
23832 let val = buf.get_f32_le();
23833 *v = val;
23834 }
23835 let tmp = buf.get_u8();
23836 __struct.frame_id =
23837 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23838 enum_type: "MavFrame",
23839 value: tmp as u32,
23840 })?;
23841 let tmp = buf.get_u8();
23842 __struct.child_frame_id =
23843 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23844 enum_type: "MavFrame",
23845 value: tmp as u32,
23846 })?;
23847 __struct.reset_counter = buf.get_u8();
23848 let tmp = buf.get_u8();
23849 __struct.estimator_type =
23850 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
23851 enum_type: "MavEstimatorType",
23852 value: tmp as u32,
23853 })?;
23854 __struct.quality = buf.get_i8();
23855 Ok(__struct)
23856 }
23857 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23858 let mut __tmp = BytesMut::new(bytes);
23859 #[allow(clippy::absurd_extreme_comparisons)]
23860 #[allow(unused_comparisons)]
23861 if __tmp.remaining() < Self::ENCODED_LEN {
23862 panic!(
23863 "buffer is too small (need {} bytes, but got {})",
23864 Self::ENCODED_LEN,
23865 __tmp.remaining(),
23866 )
23867 }
23868 __tmp.put_u64_le(self.time_usec);
23869 __tmp.put_f32_le(self.x);
23870 __tmp.put_f32_le(self.y);
23871 __tmp.put_f32_le(self.z);
23872 for val in &self.q {
23873 __tmp.put_f32_le(*val);
23874 }
23875 __tmp.put_f32_le(self.vx);
23876 __tmp.put_f32_le(self.vy);
23877 __tmp.put_f32_le(self.vz);
23878 __tmp.put_f32_le(self.rollspeed);
23879 __tmp.put_f32_le(self.pitchspeed);
23880 __tmp.put_f32_le(self.yawspeed);
23881 for val in &self.pose_covariance {
23882 __tmp.put_f32_le(*val);
23883 }
23884 for val in &self.velocity_covariance {
23885 __tmp.put_f32_le(*val);
23886 }
23887 __tmp.put_u8(self.frame_id as u8);
23888 __tmp.put_u8(self.child_frame_id as u8);
23889 __tmp.put_u8(self.reset_counter);
23890 __tmp.put_u8(self.estimator_type as u8);
23891 __tmp.put_i8(self.quality);
23892 if matches!(version, MavlinkVersion::V2) {
23893 let len = __tmp.len();
23894 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
23895 } else {
23896 __tmp.len()
23897 }
23898 }
23899}
23900#[doc = "id: 102"]
23901#[doc = "Local position/attitude estimate from a vision source."]
23902#[derive(Debug, Clone, PartialEq)]
23903#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
23904#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
23905pub struct VISION_POSITION_ESTIMATE_DATA {
23906 #[doc = "Timestamp (UNIX time or time since system boot)"]
23907 pub usec: u64,
23908 #[doc = "Local X position"]
23909 pub x: f32,
23910 #[doc = "Local Y position"]
23911 pub y: f32,
23912 #[doc = "Local Z position"]
23913 pub z: f32,
23914 #[doc = "Roll angle"]
23915 pub roll: f32,
23916 #[doc = "Pitch angle"]
23917 pub pitch: f32,
23918 #[doc = "Yaw angle"]
23919 pub yaw: f32,
23920 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
23921 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23922 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
23923 pub covariance: [f32; 21],
23924 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
23925 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
23926 pub reset_counter: u8,
23927}
23928impl VISION_POSITION_ESTIMATE_DATA {
23929 pub const ENCODED_LEN: usize = 117usize;
23930 pub const DEFAULT: Self = Self {
23931 usec: 0_u64,
23932 x: 0.0_f32,
23933 y: 0.0_f32,
23934 z: 0.0_f32,
23935 roll: 0.0_f32,
23936 pitch: 0.0_f32,
23937 yaw: 0.0_f32,
23938 covariance: [0.0_f32; 21usize],
23939 reset_counter: 0_u8,
23940 };
23941 #[cfg(feature = "arbitrary")]
23942 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
23943 use arbitrary::{Arbitrary, Unstructured};
23944 let mut buf = [0u8; 1024];
23945 rng.fill_bytes(&mut buf);
23946 let mut unstructured = Unstructured::new(&buf);
23947 Self::arbitrary(&mut unstructured).unwrap_or_default()
23948 }
23949}
23950impl Default for VISION_POSITION_ESTIMATE_DATA {
23951 fn default() -> Self {
23952 Self::DEFAULT.clone()
23953 }
23954}
23955impl MessageData for VISION_POSITION_ESTIMATE_DATA {
23956 type Message = MavMessage;
23957 const ID: u32 = 102u32;
23958 const NAME: &'static str = "VISION_POSITION_ESTIMATE";
23959 const EXTRA_CRC: u8 = 158u8;
23960 const ENCODED_LEN: usize = 117usize;
23961 fn deser(
23962 _version: MavlinkVersion,
23963 __input: &[u8],
23964 ) -> Result<Self, ::mavlink_core::error::ParserError> {
23965 let avail_len = __input.len();
23966 let mut payload_buf = [0; Self::ENCODED_LEN];
23967 let mut buf = if avail_len < Self::ENCODED_LEN {
23968 payload_buf[0..avail_len].copy_from_slice(__input);
23969 Bytes::new(&payload_buf)
23970 } else {
23971 Bytes::new(__input)
23972 };
23973 let mut __struct = Self::default();
23974 __struct.usec = buf.get_u64_le();
23975 __struct.x = buf.get_f32_le();
23976 __struct.y = buf.get_f32_le();
23977 __struct.z = buf.get_f32_le();
23978 __struct.roll = buf.get_f32_le();
23979 __struct.pitch = buf.get_f32_le();
23980 __struct.yaw = buf.get_f32_le();
23981 for v in &mut __struct.covariance {
23982 let val = buf.get_f32_le();
23983 *v = val;
23984 }
23985 __struct.reset_counter = buf.get_u8();
23986 Ok(__struct)
23987 }
23988 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
23989 let mut __tmp = BytesMut::new(bytes);
23990 #[allow(clippy::absurd_extreme_comparisons)]
23991 #[allow(unused_comparisons)]
23992 if __tmp.remaining() < Self::ENCODED_LEN {
23993 panic!(
23994 "buffer is too small (need {} bytes, but got {})",
23995 Self::ENCODED_LEN,
23996 __tmp.remaining(),
23997 )
23998 }
23999 __tmp.put_u64_le(self.usec);
24000 __tmp.put_f32_le(self.x);
24001 __tmp.put_f32_le(self.y);
24002 __tmp.put_f32_le(self.z);
24003 __tmp.put_f32_le(self.roll);
24004 __tmp.put_f32_le(self.pitch);
24005 __tmp.put_f32_le(self.yaw);
24006 for val in &self.covariance {
24007 __tmp.put_f32_le(*val);
24008 }
24009 __tmp.put_u8(self.reset_counter);
24010 if matches!(version, MavlinkVersion::V2) {
24011 let len = __tmp.len();
24012 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24013 } else {
24014 __tmp.len()
24015 }
24016 }
24017}
24018#[doc = "id: 20"]
24019#[doc = "value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also <https://mavlink.io/en/services/parameter.html> for a full documentation of QGroundControl and IMU code."]
24020#[derive(Debug, Clone, PartialEq)]
24021#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24022#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24023pub struct PARAM_REQUEST_READ_DATA {
24024 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)"]
24025 pub param_index: i16,
24026 #[doc = "System ID"]
24027 pub target_system: u8,
24028 #[doc = "Component ID"]
24029 pub target_component: u8,
24030 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
24031 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24032 pub param_id: [u8; 16],
24033}
24034impl PARAM_REQUEST_READ_DATA {
24035 pub const ENCODED_LEN: usize = 20usize;
24036 pub const DEFAULT: Self = Self {
24037 param_index: 0_i16,
24038 target_system: 0_u8,
24039 target_component: 0_u8,
24040 param_id: [0_u8; 16usize],
24041 };
24042 #[cfg(feature = "arbitrary")]
24043 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24044 use arbitrary::{Arbitrary, Unstructured};
24045 let mut buf = [0u8; 1024];
24046 rng.fill_bytes(&mut buf);
24047 let mut unstructured = Unstructured::new(&buf);
24048 Self::arbitrary(&mut unstructured).unwrap_or_default()
24049 }
24050}
24051impl Default for PARAM_REQUEST_READ_DATA {
24052 fn default() -> Self {
24053 Self::DEFAULT.clone()
24054 }
24055}
24056impl MessageData for PARAM_REQUEST_READ_DATA {
24057 type Message = MavMessage;
24058 const ID: u32 = 20u32;
24059 const NAME: &'static str = "PARAM_REQUEST_READ";
24060 const EXTRA_CRC: u8 = 214u8;
24061 const ENCODED_LEN: usize = 20usize;
24062 fn deser(
24063 _version: MavlinkVersion,
24064 __input: &[u8],
24065 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24066 let avail_len = __input.len();
24067 let mut payload_buf = [0; Self::ENCODED_LEN];
24068 let mut buf = if avail_len < Self::ENCODED_LEN {
24069 payload_buf[0..avail_len].copy_from_slice(__input);
24070 Bytes::new(&payload_buf)
24071 } else {
24072 Bytes::new(__input)
24073 };
24074 let mut __struct = Self::default();
24075 __struct.param_index = buf.get_i16_le();
24076 __struct.target_system = buf.get_u8();
24077 __struct.target_component = buf.get_u8();
24078 for v in &mut __struct.param_id {
24079 let val = buf.get_u8();
24080 *v = val;
24081 }
24082 Ok(__struct)
24083 }
24084 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24085 let mut __tmp = BytesMut::new(bytes);
24086 #[allow(clippy::absurd_extreme_comparisons)]
24087 #[allow(unused_comparisons)]
24088 if __tmp.remaining() < Self::ENCODED_LEN {
24089 panic!(
24090 "buffer is too small (need {} bytes, but got {})",
24091 Self::ENCODED_LEN,
24092 __tmp.remaining(),
24093 )
24094 }
24095 __tmp.put_i16_le(self.param_index);
24096 __tmp.put_u8(self.target_system);
24097 __tmp.put_u8(self.target_component);
24098 for val in &self.param_id {
24099 __tmp.put_u8(*val);
24100 }
24101 if matches!(version, MavlinkVersion::V2) {
24102 let len = __tmp.len();
24103 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24104 } else {
24105 __tmp.len()
24106 }
24107 }
24108}
24109#[doc = "id: 372"]
24110#[doc = "Battery information that is static, or requires infrequent update. This message should requested using MAV_CMD_REQUEST_MESSAGE and/or streamed at very low rate. BATTERY_STATUS_V2 is used for higher-rate battery status information."]
24111#[derive(Debug, Clone, PartialEq)]
24112#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24113#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24114pub struct BATTERY_INFO_DATA {
24115 #[doc = "Minimum per-cell voltage when discharging. 0: field not provided."]
24116 pub discharge_minimum_voltage: f32,
24117 #[doc = "Minimum per-cell voltage when charging. 0: field not provided."]
24118 pub charging_minimum_voltage: f32,
24119 #[doc = "Minimum per-cell voltage when resting. 0: field not provided."]
24120 pub resting_minimum_voltage: f32,
24121 #[doc = "Maximum per-cell voltage when charged. 0: field not provided."]
24122 pub charging_maximum_voltage: f32,
24123 #[doc = "Maximum pack continuous charge current. 0: field not provided."]
24124 pub charging_maximum_current: f32,
24125 #[doc = "Battery nominal voltage. Used for conversion between Wh and Ah. 0: field not provided."]
24126 pub nominal_voltage: f32,
24127 #[doc = "Maximum pack discharge current. 0: field not provided."]
24128 pub discharge_maximum_current: f32,
24129 #[doc = "Maximum pack discharge burst current. 0: field not provided."]
24130 pub discharge_maximum_burst_current: f32,
24131 #[doc = "Fully charged design capacity. 0: field not provided."]
24132 pub design_capacity: f32,
24133 #[doc = "Predicted battery capacity when fully charged (accounting for battery degradation). NAN: field not provided."]
24134 pub full_charge_capacity: f32,
24135 #[doc = "Lifetime count of the number of charge/discharge cycles (<https://en.wikipedia.org/wiki/Charge_cycle>). UINT16_MAX: field not provided."]
24136 pub cycle_count: u16,
24137 #[doc = "Battery weight. 0: field not provided."]
24138 pub weight: u16,
24139 #[doc = "Battery ID"]
24140 pub id: u8,
24141 #[doc = "Function of the battery."]
24142 pub battery_function: MavBatteryFunction,
24143 #[doc = "Type (chemistry) of the battery."]
24144 pub mavtype: MavBatteryType,
24145 #[doc = "State of Health (SOH) estimate. Typically 100% at the time of manufacture and will decrease over time and use. -1: field not provided."]
24146 pub state_of_health: u8,
24147 #[doc = "Number of battery cells in series. 0: field not provided."]
24148 pub cells_in_series: u8,
24149 #[doc = "Manufacture date (DDMMYYYY) in ASCII characters, 0 terminated. All 0: field not provided."]
24150 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24151 pub manufacture_date: [u8; 9],
24152 #[doc = "Serial number in ASCII characters, 0 terminated. All 0: field not provided."]
24153 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24154 pub serial_number: [u8; 32],
24155 #[doc = "Battery device name. Formatted as manufacturer name then product name, separated with an underscore (in ASCII characters), 0 terminated. All 0: field not provided."]
24156 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24157 pub name: [u8; 50],
24158}
24159impl BATTERY_INFO_DATA {
24160 pub const ENCODED_LEN: usize = 140usize;
24161 pub const DEFAULT: Self = Self {
24162 discharge_minimum_voltage: 0.0_f32,
24163 charging_minimum_voltage: 0.0_f32,
24164 resting_minimum_voltage: 0.0_f32,
24165 charging_maximum_voltage: 0.0_f32,
24166 charging_maximum_current: 0.0_f32,
24167 nominal_voltage: 0.0_f32,
24168 discharge_maximum_current: 0.0_f32,
24169 discharge_maximum_burst_current: 0.0_f32,
24170 design_capacity: 0.0_f32,
24171 full_charge_capacity: 0.0_f32,
24172 cycle_count: 0_u16,
24173 weight: 0_u16,
24174 id: 0_u8,
24175 battery_function: MavBatteryFunction::DEFAULT,
24176 mavtype: MavBatteryType::DEFAULT,
24177 state_of_health: 0_u8,
24178 cells_in_series: 0_u8,
24179 manufacture_date: [0_u8; 9usize],
24180 serial_number: [0_u8; 32usize],
24181 name: [0_u8; 50usize],
24182 };
24183 #[cfg(feature = "arbitrary")]
24184 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24185 use arbitrary::{Arbitrary, Unstructured};
24186 let mut buf = [0u8; 1024];
24187 rng.fill_bytes(&mut buf);
24188 let mut unstructured = Unstructured::new(&buf);
24189 Self::arbitrary(&mut unstructured).unwrap_or_default()
24190 }
24191}
24192impl Default for BATTERY_INFO_DATA {
24193 fn default() -> Self {
24194 Self::DEFAULT.clone()
24195 }
24196}
24197impl MessageData for BATTERY_INFO_DATA {
24198 type Message = MavMessage;
24199 const ID: u32 = 372u32;
24200 const NAME: &'static str = "BATTERY_INFO";
24201 const EXTRA_CRC: u8 = 26u8;
24202 const ENCODED_LEN: usize = 140usize;
24203 fn deser(
24204 _version: MavlinkVersion,
24205 __input: &[u8],
24206 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24207 let avail_len = __input.len();
24208 let mut payload_buf = [0; Self::ENCODED_LEN];
24209 let mut buf = if avail_len < Self::ENCODED_LEN {
24210 payload_buf[0..avail_len].copy_from_slice(__input);
24211 Bytes::new(&payload_buf)
24212 } else {
24213 Bytes::new(__input)
24214 };
24215 let mut __struct = Self::default();
24216 __struct.discharge_minimum_voltage = buf.get_f32_le();
24217 __struct.charging_minimum_voltage = buf.get_f32_le();
24218 __struct.resting_minimum_voltage = buf.get_f32_le();
24219 __struct.charging_maximum_voltage = buf.get_f32_le();
24220 __struct.charging_maximum_current = buf.get_f32_le();
24221 __struct.nominal_voltage = buf.get_f32_le();
24222 __struct.discharge_maximum_current = buf.get_f32_le();
24223 __struct.discharge_maximum_burst_current = buf.get_f32_le();
24224 __struct.design_capacity = buf.get_f32_le();
24225 __struct.full_charge_capacity = buf.get_f32_le();
24226 __struct.cycle_count = buf.get_u16_le();
24227 __struct.weight = buf.get_u16_le();
24228 __struct.id = buf.get_u8();
24229 let tmp = buf.get_u8();
24230 __struct.battery_function =
24231 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24232 enum_type: "MavBatteryFunction",
24233 value: tmp as u32,
24234 })?;
24235 let tmp = buf.get_u8();
24236 __struct.mavtype =
24237 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24238 enum_type: "MavBatteryType",
24239 value: tmp as u32,
24240 })?;
24241 __struct.state_of_health = buf.get_u8();
24242 __struct.cells_in_series = buf.get_u8();
24243 for v in &mut __struct.manufacture_date {
24244 let val = buf.get_u8();
24245 *v = val;
24246 }
24247 for v in &mut __struct.serial_number {
24248 let val = buf.get_u8();
24249 *v = val;
24250 }
24251 for v in &mut __struct.name {
24252 let val = buf.get_u8();
24253 *v = val;
24254 }
24255 Ok(__struct)
24256 }
24257 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24258 let mut __tmp = BytesMut::new(bytes);
24259 #[allow(clippy::absurd_extreme_comparisons)]
24260 #[allow(unused_comparisons)]
24261 if __tmp.remaining() < Self::ENCODED_LEN {
24262 panic!(
24263 "buffer is too small (need {} bytes, but got {})",
24264 Self::ENCODED_LEN,
24265 __tmp.remaining(),
24266 )
24267 }
24268 __tmp.put_f32_le(self.discharge_minimum_voltage);
24269 __tmp.put_f32_le(self.charging_minimum_voltage);
24270 __tmp.put_f32_le(self.resting_minimum_voltage);
24271 __tmp.put_f32_le(self.charging_maximum_voltage);
24272 __tmp.put_f32_le(self.charging_maximum_current);
24273 __tmp.put_f32_le(self.nominal_voltage);
24274 __tmp.put_f32_le(self.discharge_maximum_current);
24275 __tmp.put_f32_le(self.discharge_maximum_burst_current);
24276 __tmp.put_f32_le(self.design_capacity);
24277 __tmp.put_f32_le(self.full_charge_capacity);
24278 __tmp.put_u16_le(self.cycle_count);
24279 __tmp.put_u16_le(self.weight);
24280 __tmp.put_u8(self.id);
24281 __tmp.put_u8(self.battery_function as u8);
24282 __tmp.put_u8(self.mavtype as u8);
24283 __tmp.put_u8(self.state_of_health);
24284 __tmp.put_u8(self.cells_in_series);
24285 for val in &self.manufacture_date {
24286 __tmp.put_u8(*val);
24287 }
24288 for val in &self.serial_number {
24289 __tmp.put_u8(*val);
24290 }
24291 for val in &self.name {
24292 __tmp.put_u8(*val);
24293 }
24294 if matches!(version, MavlinkVersion::V2) {
24295 let len = __tmp.len();
24296 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24297 } else {
24298 __tmp.len()
24299 }
24300 }
24301}
24302#[doc = "id: 89"]
24303#[doc = "The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)."]
24304#[derive(Debug, Clone, PartialEq)]
24305#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24306#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24307pub struct LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
24308 #[doc = "Timestamp (time since system boot)."]
24309 pub time_boot_ms: u32,
24310 #[doc = "X Position"]
24311 pub x: f32,
24312 #[doc = "Y Position"]
24313 pub y: f32,
24314 #[doc = "Z Position"]
24315 pub z: f32,
24316 #[doc = "Roll"]
24317 pub roll: f32,
24318 #[doc = "Pitch"]
24319 pub pitch: f32,
24320 #[doc = "Yaw"]
24321 pub yaw: f32,
24322}
24323impl LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
24324 pub const ENCODED_LEN: usize = 28usize;
24325 pub const DEFAULT: Self = Self {
24326 time_boot_ms: 0_u32,
24327 x: 0.0_f32,
24328 y: 0.0_f32,
24329 z: 0.0_f32,
24330 roll: 0.0_f32,
24331 pitch: 0.0_f32,
24332 yaw: 0.0_f32,
24333 };
24334 #[cfg(feature = "arbitrary")]
24335 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24336 use arbitrary::{Arbitrary, Unstructured};
24337 let mut buf = [0u8; 1024];
24338 rng.fill_bytes(&mut buf);
24339 let mut unstructured = Unstructured::new(&buf);
24340 Self::arbitrary(&mut unstructured).unwrap_or_default()
24341 }
24342}
24343impl Default for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
24344 fn default() -> Self {
24345 Self::DEFAULT.clone()
24346 }
24347}
24348impl MessageData for LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA {
24349 type Message = MavMessage;
24350 const ID: u32 = 89u32;
24351 const NAME: &'static str = "LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET";
24352 const EXTRA_CRC: u8 = 231u8;
24353 const ENCODED_LEN: usize = 28usize;
24354 fn deser(
24355 _version: MavlinkVersion,
24356 __input: &[u8],
24357 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24358 let avail_len = __input.len();
24359 let mut payload_buf = [0; Self::ENCODED_LEN];
24360 let mut buf = if avail_len < Self::ENCODED_LEN {
24361 payload_buf[0..avail_len].copy_from_slice(__input);
24362 Bytes::new(&payload_buf)
24363 } else {
24364 Bytes::new(__input)
24365 };
24366 let mut __struct = Self::default();
24367 __struct.time_boot_ms = buf.get_u32_le();
24368 __struct.x = buf.get_f32_le();
24369 __struct.y = buf.get_f32_le();
24370 __struct.z = buf.get_f32_le();
24371 __struct.roll = buf.get_f32_le();
24372 __struct.pitch = buf.get_f32_le();
24373 __struct.yaw = buf.get_f32_le();
24374 Ok(__struct)
24375 }
24376 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24377 let mut __tmp = BytesMut::new(bytes);
24378 #[allow(clippy::absurd_extreme_comparisons)]
24379 #[allow(unused_comparisons)]
24380 if __tmp.remaining() < Self::ENCODED_LEN {
24381 panic!(
24382 "buffer is too small (need {} bytes, but got {})",
24383 Self::ENCODED_LEN,
24384 __tmp.remaining(),
24385 )
24386 }
24387 __tmp.put_u32_le(self.time_boot_ms);
24388 __tmp.put_f32_le(self.x);
24389 __tmp.put_f32_le(self.y);
24390 __tmp.put_f32_le(self.z);
24391 __tmp.put_f32_le(self.roll);
24392 __tmp.put_f32_le(self.pitch);
24393 __tmp.put_f32_le(self.yaw);
24394 if matches!(version, MavlinkVersion::V2) {
24395 let len = __tmp.len();
24396 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24397 } else {
24398 __tmp.len()
24399 }
24400 }
24401}
24402#[doc = "id: 270"]
24403#[doc = "Information about the status of a video stream. It may be requested using MAV_CMD_REQUEST_MESSAGE."]
24404#[derive(Debug, Clone, PartialEq)]
24405#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24406#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24407pub struct VIDEO_STREAM_STATUS_DATA {
24408 #[doc = "Frame rate"]
24409 pub framerate: f32,
24410 #[doc = "Bit rate"]
24411 pub bitrate: u32,
24412 #[doc = "Bitmap of stream status flags"]
24413 pub flags: VideoStreamStatusFlags,
24414 #[doc = "Horizontal resolution"]
24415 pub resolution_h: u16,
24416 #[doc = "Vertical resolution"]
24417 pub resolution_v: u16,
24418 #[doc = "Video image rotation clockwise"]
24419 pub rotation: u16,
24420 #[doc = "Horizontal Field of view"]
24421 pub hfov: u16,
24422 #[doc = "Video Stream ID (1 for first, 2 for second, etc.)"]
24423 pub stream_id: u8,
24424 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
24425 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24426 pub camera_device_id: u8,
24427}
24428impl VIDEO_STREAM_STATUS_DATA {
24429 pub const ENCODED_LEN: usize = 20usize;
24430 pub const DEFAULT: Self = Self {
24431 framerate: 0.0_f32,
24432 bitrate: 0_u32,
24433 flags: VideoStreamStatusFlags::DEFAULT,
24434 resolution_h: 0_u16,
24435 resolution_v: 0_u16,
24436 rotation: 0_u16,
24437 hfov: 0_u16,
24438 stream_id: 0_u8,
24439 camera_device_id: 0_u8,
24440 };
24441 #[cfg(feature = "arbitrary")]
24442 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24443 use arbitrary::{Arbitrary, Unstructured};
24444 let mut buf = [0u8; 1024];
24445 rng.fill_bytes(&mut buf);
24446 let mut unstructured = Unstructured::new(&buf);
24447 Self::arbitrary(&mut unstructured).unwrap_or_default()
24448 }
24449}
24450impl Default for VIDEO_STREAM_STATUS_DATA {
24451 fn default() -> Self {
24452 Self::DEFAULT.clone()
24453 }
24454}
24455impl MessageData for VIDEO_STREAM_STATUS_DATA {
24456 type Message = MavMessage;
24457 const ID: u32 = 270u32;
24458 const NAME: &'static str = "VIDEO_STREAM_STATUS";
24459 const EXTRA_CRC: u8 = 59u8;
24460 const ENCODED_LEN: usize = 20usize;
24461 fn deser(
24462 _version: MavlinkVersion,
24463 __input: &[u8],
24464 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24465 let avail_len = __input.len();
24466 let mut payload_buf = [0; Self::ENCODED_LEN];
24467 let mut buf = if avail_len < Self::ENCODED_LEN {
24468 payload_buf[0..avail_len].copy_from_slice(__input);
24469 Bytes::new(&payload_buf)
24470 } else {
24471 Bytes::new(__input)
24472 };
24473 let mut __struct = Self::default();
24474 __struct.framerate = buf.get_f32_le();
24475 __struct.bitrate = buf.get_u32_le();
24476 let tmp = buf.get_u16_le();
24477 __struct.flags = VideoStreamStatusFlags::from_bits(
24478 tmp & VideoStreamStatusFlags::all().bits(),
24479 )
24480 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
24481 flag_type: "VideoStreamStatusFlags",
24482 value: tmp as u32,
24483 })?;
24484 __struct.resolution_h = buf.get_u16_le();
24485 __struct.resolution_v = buf.get_u16_le();
24486 __struct.rotation = buf.get_u16_le();
24487 __struct.hfov = buf.get_u16_le();
24488 __struct.stream_id = buf.get_u8();
24489 __struct.camera_device_id = buf.get_u8();
24490 Ok(__struct)
24491 }
24492 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24493 let mut __tmp = BytesMut::new(bytes);
24494 #[allow(clippy::absurd_extreme_comparisons)]
24495 #[allow(unused_comparisons)]
24496 if __tmp.remaining() < Self::ENCODED_LEN {
24497 panic!(
24498 "buffer is too small (need {} bytes, but got {})",
24499 Self::ENCODED_LEN,
24500 __tmp.remaining(),
24501 )
24502 }
24503 __tmp.put_f32_le(self.framerate);
24504 __tmp.put_u32_le(self.bitrate);
24505 __tmp.put_u16_le(self.flags.bits());
24506 __tmp.put_u16_le(self.resolution_h);
24507 __tmp.put_u16_le(self.resolution_v);
24508 __tmp.put_u16_le(self.rotation);
24509 __tmp.put_u16_le(self.hfov);
24510 __tmp.put_u8(self.stream_id);
24511 __tmp.put_u8(self.camera_device_id);
24512 if matches!(version, MavlinkVersion::V2) {
24513 let len = __tmp.len();
24514 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24515 } else {
24516 __tmp.len()
24517 }
24518 }
24519}
24520#[doc = "id: 138"]
24521#[doc = "Motion capture attitude and position."]
24522#[derive(Debug, Clone, PartialEq)]
24523#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24524#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24525pub struct ATT_POS_MOCAP_DATA {
24526 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
24527 pub time_usec: u64,
24528 #[doc = "Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
24529 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24530 pub q: [f32; 4],
24531 #[doc = "X position (NED)"]
24532 pub x: f32,
24533 #[doc = "Y position (NED)"]
24534 pub y: f32,
24535 #[doc = "Z position (NED)"]
24536 pub z: f32,
24537 #[doc = "Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
24538 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24539 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24540 pub covariance: [f32; 21],
24541}
24542impl ATT_POS_MOCAP_DATA {
24543 pub const ENCODED_LEN: usize = 120usize;
24544 pub const DEFAULT: Self = Self {
24545 time_usec: 0_u64,
24546 q: [0.0_f32; 4usize],
24547 x: 0.0_f32,
24548 y: 0.0_f32,
24549 z: 0.0_f32,
24550 covariance: [0.0_f32; 21usize],
24551 };
24552 #[cfg(feature = "arbitrary")]
24553 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24554 use arbitrary::{Arbitrary, Unstructured};
24555 let mut buf = [0u8; 1024];
24556 rng.fill_bytes(&mut buf);
24557 let mut unstructured = Unstructured::new(&buf);
24558 Self::arbitrary(&mut unstructured).unwrap_or_default()
24559 }
24560}
24561impl Default for ATT_POS_MOCAP_DATA {
24562 fn default() -> Self {
24563 Self::DEFAULT.clone()
24564 }
24565}
24566impl MessageData for ATT_POS_MOCAP_DATA {
24567 type Message = MavMessage;
24568 const ID: u32 = 138u32;
24569 const NAME: &'static str = "ATT_POS_MOCAP";
24570 const EXTRA_CRC: u8 = 109u8;
24571 const ENCODED_LEN: usize = 120usize;
24572 fn deser(
24573 _version: MavlinkVersion,
24574 __input: &[u8],
24575 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24576 let avail_len = __input.len();
24577 let mut payload_buf = [0; Self::ENCODED_LEN];
24578 let mut buf = if avail_len < Self::ENCODED_LEN {
24579 payload_buf[0..avail_len].copy_from_slice(__input);
24580 Bytes::new(&payload_buf)
24581 } else {
24582 Bytes::new(__input)
24583 };
24584 let mut __struct = Self::default();
24585 __struct.time_usec = buf.get_u64_le();
24586 for v in &mut __struct.q {
24587 let val = buf.get_f32_le();
24588 *v = val;
24589 }
24590 __struct.x = buf.get_f32_le();
24591 __struct.y = buf.get_f32_le();
24592 __struct.z = buf.get_f32_le();
24593 for v in &mut __struct.covariance {
24594 let val = buf.get_f32_le();
24595 *v = val;
24596 }
24597 Ok(__struct)
24598 }
24599 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24600 let mut __tmp = BytesMut::new(bytes);
24601 #[allow(clippy::absurd_extreme_comparisons)]
24602 #[allow(unused_comparisons)]
24603 if __tmp.remaining() < Self::ENCODED_LEN {
24604 panic!(
24605 "buffer is too small (need {} bytes, but got {})",
24606 Self::ENCODED_LEN,
24607 __tmp.remaining(),
24608 )
24609 }
24610 __tmp.put_u64_le(self.time_usec);
24611 for val in &self.q {
24612 __tmp.put_f32_le(*val);
24613 }
24614 __tmp.put_f32_le(self.x);
24615 __tmp.put_f32_le(self.y);
24616 __tmp.put_f32_le(self.z);
24617 for val in &self.covariance {
24618 __tmp.put_f32_le(*val);
24619 }
24620 if matches!(version, MavlinkVersion::V2) {
24621 let len = __tmp.len();
24622 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24623 } else {
24624 __tmp.len()
24625 }
24626 }
24627}
24628#[doc = "id: 10006"]
24629#[doc = "Request messages."]
24630#[derive(Debug, Clone, PartialEq)]
24631#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24632#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24633pub struct UAVIONIX_ADSB_GET_DATA {
24634 #[doc = "Message ID to request. Supports any message in this 10000-10099 range"]
24635 pub ReqMessageId: u32,
24636}
24637impl UAVIONIX_ADSB_GET_DATA {
24638 pub const ENCODED_LEN: usize = 4usize;
24639 pub const DEFAULT: Self = Self {
24640 ReqMessageId: 0_u32,
24641 };
24642 #[cfg(feature = "arbitrary")]
24643 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24644 use arbitrary::{Arbitrary, Unstructured};
24645 let mut buf = [0u8; 1024];
24646 rng.fill_bytes(&mut buf);
24647 let mut unstructured = Unstructured::new(&buf);
24648 Self::arbitrary(&mut unstructured).unwrap_or_default()
24649 }
24650}
24651impl Default for UAVIONIX_ADSB_GET_DATA {
24652 fn default() -> Self {
24653 Self::DEFAULT.clone()
24654 }
24655}
24656impl MessageData for UAVIONIX_ADSB_GET_DATA {
24657 type Message = MavMessage;
24658 const ID: u32 = 10006u32;
24659 const NAME: &'static str = "UAVIONIX_ADSB_GET";
24660 const EXTRA_CRC: u8 = 193u8;
24661 const ENCODED_LEN: usize = 4usize;
24662 fn deser(
24663 _version: MavlinkVersion,
24664 __input: &[u8],
24665 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24666 let avail_len = __input.len();
24667 let mut payload_buf = [0; Self::ENCODED_LEN];
24668 let mut buf = if avail_len < Self::ENCODED_LEN {
24669 payload_buf[0..avail_len].copy_from_slice(__input);
24670 Bytes::new(&payload_buf)
24671 } else {
24672 Bytes::new(__input)
24673 };
24674 let mut __struct = Self::default();
24675 __struct.ReqMessageId = buf.get_u32_le();
24676 Ok(__struct)
24677 }
24678 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24679 let mut __tmp = BytesMut::new(bytes);
24680 #[allow(clippy::absurd_extreme_comparisons)]
24681 #[allow(unused_comparisons)]
24682 if __tmp.remaining() < Self::ENCODED_LEN {
24683 panic!(
24684 "buffer is too small (need {} bytes, but got {})",
24685 Self::ENCODED_LEN,
24686 __tmp.remaining(),
24687 )
24688 }
24689 __tmp.put_u32_le(self.ReqMessageId);
24690 if matches!(version, MavlinkVersion::V2) {
24691 let len = __tmp.len();
24692 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24693 } else {
24694 __tmp.len()
24695 }
24696 }
24697}
24698#[doc = "id: 39"]
24699#[doc = "Message encoding a mission item. This message is emitted to announce the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). NaN may be used to indicate an optional/default value (e.g. to use the system's current latitude or yaw rather than a specific value). See also <https://mavlink.io/en/services/mission.html>."]
24700#[derive(Debug, Clone, PartialEq)]
24701#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24702#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24703pub struct MISSION_ITEM_DATA {
24704 #[doc = "PARAM1, see MAV_CMD enum"]
24705 pub param1: f32,
24706 #[doc = "PARAM2, see MAV_CMD enum"]
24707 pub param2: f32,
24708 #[doc = "PARAM3, see MAV_CMD enum"]
24709 pub param3: f32,
24710 #[doc = "PARAM4, see MAV_CMD enum"]
24711 pub param4: f32,
24712 #[doc = "PARAM5 / local: X coordinate, global: latitude"]
24713 pub x: f32,
24714 #[doc = "PARAM6 / local: Y coordinate, global: longitude"]
24715 pub y: f32,
24716 #[doc = "PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame)."]
24717 pub z: f32,
24718 #[doc = "Sequence"]
24719 pub seq: u16,
24720 #[doc = "The scheduled action for the waypoint."]
24721 pub command: MavCmd,
24722 #[doc = "System ID"]
24723 pub target_system: u8,
24724 #[doc = "Component ID"]
24725 pub target_component: u8,
24726 #[doc = "The coordinate system of the waypoint."]
24727 pub frame: MavFrame,
24728 #[doc = "false:0, true:1"]
24729 pub current: u8,
24730 #[doc = "Autocontinue to next waypoint. 0: false, 1: true. Set false to pause mission after the item completes."]
24731 pub autocontinue: u8,
24732 #[doc = "Mission type."]
24733 #[cfg_attr(feature = "serde", serde(default))]
24734 pub mission_type: MavMissionType,
24735}
24736impl MISSION_ITEM_DATA {
24737 pub const ENCODED_LEN: usize = 38usize;
24738 pub const DEFAULT: Self = Self {
24739 param1: 0.0_f32,
24740 param2: 0.0_f32,
24741 param3: 0.0_f32,
24742 param4: 0.0_f32,
24743 x: 0.0_f32,
24744 y: 0.0_f32,
24745 z: 0.0_f32,
24746 seq: 0_u16,
24747 command: MavCmd::DEFAULT,
24748 target_system: 0_u8,
24749 target_component: 0_u8,
24750 frame: MavFrame::DEFAULT,
24751 current: 0_u8,
24752 autocontinue: 0_u8,
24753 mission_type: MavMissionType::DEFAULT,
24754 };
24755 #[cfg(feature = "arbitrary")]
24756 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24757 use arbitrary::{Arbitrary, Unstructured};
24758 let mut buf = [0u8; 1024];
24759 rng.fill_bytes(&mut buf);
24760 let mut unstructured = Unstructured::new(&buf);
24761 Self::arbitrary(&mut unstructured).unwrap_or_default()
24762 }
24763}
24764impl Default for MISSION_ITEM_DATA {
24765 fn default() -> Self {
24766 Self::DEFAULT.clone()
24767 }
24768}
24769impl MessageData for MISSION_ITEM_DATA {
24770 type Message = MavMessage;
24771 const ID: u32 = 39u32;
24772 const NAME: &'static str = "MISSION_ITEM";
24773 const EXTRA_CRC: u8 = 254u8;
24774 const ENCODED_LEN: usize = 38usize;
24775 fn deser(
24776 _version: MavlinkVersion,
24777 __input: &[u8],
24778 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24779 let avail_len = __input.len();
24780 let mut payload_buf = [0; Self::ENCODED_LEN];
24781 let mut buf = if avail_len < Self::ENCODED_LEN {
24782 payload_buf[0..avail_len].copy_from_slice(__input);
24783 Bytes::new(&payload_buf)
24784 } else {
24785 Bytes::new(__input)
24786 };
24787 let mut __struct = Self::default();
24788 __struct.param1 = buf.get_f32_le();
24789 __struct.param2 = buf.get_f32_le();
24790 __struct.param3 = buf.get_f32_le();
24791 __struct.param4 = buf.get_f32_le();
24792 __struct.x = buf.get_f32_le();
24793 __struct.y = buf.get_f32_le();
24794 __struct.z = buf.get_f32_le();
24795 __struct.seq = buf.get_u16_le();
24796 let tmp = buf.get_u16_le();
24797 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
24798 ::mavlink_core::error::ParserError::InvalidEnum {
24799 enum_type: "MavCmd",
24800 value: tmp as u32,
24801 },
24802 )?;
24803 __struct.target_system = buf.get_u8();
24804 __struct.target_component = buf.get_u8();
24805 let tmp = buf.get_u8();
24806 __struct.frame =
24807 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24808 enum_type: "MavFrame",
24809 value: tmp as u32,
24810 })?;
24811 __struct.current = buf.get_u8();
24812 __struct.autocontinue = buf.get_u8();
24813 let tmp = buf.get_u8();
24814 __struct.mission_type =
24815 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
24816 enum_type: "MavMissionType",
24817 value: tmp as u32,
24818 })?;
24819 Ok(__struct)
24820 }
24821 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24822 let mut __tmp = BytesMut::new(bytes);
24823 #[allow(clippy::absurd_extreme_comparisons)]
24824 #[allow(unused_comparisons)]
24825 if __tmp.remaining() < Self::ENCODED_LEN {
24826 panic!(
24827 "buffer is too small (need {} bytes, but got {})",
24828 Self::ENCODED_LEN,
24829 __tmp.remaining(),
24830 )
24831 }
24832 __tmp.put_f32_le(self.param1);
24833 __tmp.put_f32_le(self.param2);
24834 __tmp.put_f32_le(self.param3);
24835 __tmp.put_f32_le(self.param4);
24836 __tmp.put_f32_le(self.x);
24837 __tmp.put_f32_le(self.y);
24838 __tmp.put_f32_le(self.z);
24839 __tmp.put_u16_le(self.seq);
24840 __tmp.put_u16_le(self.command as u16);
24841 __tmp.put_u8(self.target_system);
24842 __tmp.put_u8(self.target_component);
24843 __tmp.put_u8(self.frame as u8);
24844 __tmp.put_u8(self.current);
24845 __tmp.put_u8(self.autocontinue);
24846 __tmp.put_u8(self.mission_type as u8);
24847 if matches!(version, MavlinkVersion::V2) {
24848 let len = __tmp.len();
24849 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24850 } else {
24851 __tmp.len()
24852 }
24853 }
24854}
24855#[doc = "id: 103"]
24856#[doc = "Speed estimate from a vision source."]
24857#[derive(Debug, Clone, PartialEq)]
24858#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24859#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24860pub struct VISION_SPEED_ESTIMATE_DATA {
24861 #[doc = "Timestamp (UNIX time or time since system boot)"]
24862 pub usec: u64,
24863 #[doc = "Global X speed"]
24864 pub x: f32,
24865 #[doc = "Global Y speed"]
24866 pub y: f32,
24867 #[doc = "Global Z speed"]
24868 pub z: f32,
24869 #[doc = "Row-major representation of 3x3 linear velocity covariance matrix (states: vx, vy, vz; 1st three entries - 1st row, etc.). If unknown, assign NaN value to first element in the array."]
24870 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24871 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
24872 pub covariance: [f32; 9],
24873 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
24874 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
24875 pub reset_counter: u8,
24876}
24877impl VISION_SPEED_ESTIMATE_DATA {
24878 pub const ENCODED_LEN: usize = 57usize;
24879 pub const DEFAULT: Self = Self {
24880 usec: 0_u64,
24881 x: 0.0_f32,
24882 y: 0.0_f32,
24883 z: 0.0_f32,
24884 covariance: [0.0_f32; 9usize],
24885 reset_counter: 0_u8,
24886 };
24887 #[cfg(feature = "arbitrary")]
24888 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24889 use arbitrary::{Arbitrary, Unstructured};
24890 let mut buf = [0u8; 1024];
24891 rng.fill_bytes(&mut buf);
24892 let mut unstructured = Unstructured::new(&buf);
24893 Self::arbitrary(&mut unstructured).unwrap_or_default()
24894 }
24895}
24896impl Default for VISION_SPEED_ESTIMATE_DATA {
24897 fn default() -> Self {
24898 Self::DEFAULT.clone()
24899 }
24900}
24901impl MessageData for VISION_SPEED_ESTIMATE_DATA {
24902 type Message = MavMessage;
24903 const ID: u32 = 103u32;
24904 const NAME: &'static str = "VISION_SPEED_ESTIMATE";
24905 const EXTRA_CRC: u8 = 208u8;
24906 const ENCODED_LEN: usize = 57usize;
24907 fn deser(
24908 _version: MavlinkVersion,
24909 __input: &[u8],
24910 ) -> Result<Self, ::mavlink_core::error::ParserError> {
24911 let avail_len = __input.len();
24912 let mut payload_buf = [0; Self::ENCODED_LEN];
24913 let mut buf = if avail_len < Self::ENCODED_LEN {
24914 payload_buf[0..avail_len].copy_from_slice(__input);
24915 Bytes::new(&payload_buf)
24916 } else {
24917 Bytes::new(__input)
24918 };
24919 let mut __struct = Self::default();
24920 __struct.usec = buf.get_u64_le();
24921 __struct.x = buf.get_f32_le();
24922 __struct.y = buf.get_f32_le();
24923 __struct.z = buf.get_f32_le();
24924 for v in &mut __struct.covariance {
24925 let val = buf.get_f32_le();
24926 *v = val;
24927 }
24928 __struct.reset_counter = buf.get_u8();
24929 Ok(__struct)
24930 }
24931 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
24932 let mut __tmp = BytesMut::new(bytes);
24933 #[allow(clippy::absurd_extreme_comparisons)]
24934 #[allow(unused_comparisons)]
24935 if __tmp.remaining() < Self::ENCODED_LEN {
24936 panic!(
24937 "buffer is too small (need {} bytes, but got {})",
24938 Self::ENCODED_LEN,
24939 __tmp.remaining(),
24940 )
24941 }
24942 __tmp.put_u64_le(self.usec);
24943 __tmp.put_f32_le(self.x);
24944 __tmp.put_f32_le(self.y);
24945 __tmp.put_f32_le(self.z);
24946 for val in &self.covariance {
24947 __tmp.put_f32_le(*val);
24948 }
24949 __tmp.put_u8(self.reset_counter);
24950 if matches!(version, MavlinkVersion::V2) {
24951 let len = __tmp.len();
24952 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
24953 } else {
24954 __tmp.len()
24955 }
24956 }
24957}
24958#[doc = "id: 38"]
24959#[doc = "This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!."]
24960#[derive(Debug, Clone, PartialEq)]
24961#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
24962#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
24963pub struct MISSION_WRITE_PARTIAL_LIST_DATA {
24964 #[doc = "Start index. Must be smaller / equal to the largest index of the current onboard list."]
24965 pub start_index: i16,
24966 #[doc = "End index, equal or greater than start index."]
24967 pub end_index: i16,
24968 #[doc = "System ID"]
24969 pub target_system: u8,
24970 #[doc = "Component ID"]
24971 pub target_component: u8,
24972 #[doc = "Mission type."]
24973 #[cfg_attr(feature = "serde", serde(default))]
24974 pub mission_type: MavMissionType,
24975}
24976impl MISSION_WRITE_PARTIAL_LIST_DATA {
24977 pub const ENCODED_LEN: usize = 7usize;
24978 pub const DEFAULT: Self = Self {
24979 start_index: 0_i16,
24980 end_index: 0_i16,
24981 target_system: 0_u8,
24982 target_component: 0_u8,
24983 mission_type: MavMissionType::DEFAULT,
24984 };
24985 #[cfg(feature = "arbitrary")]
24986 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
24987 use arbitrary::{Arbitrary, Unstructured};
24988 let mut buf = [0u8; 1024];
24989 rng.fill_bytes(&mut buf);
24990 let mut unstructured = Unstructured::new(&buf);
24991 Self::arbitrary(&mut unstructured).unwrap_or_default()
24992 }
24993}
24994impl Default for MISSION_WRITE_PARTIAL_LIST_DATA {
24995 fn default() -> Self {
24996 Self::DEFAULT.clone()
24997 }
24998}
24999impl MessageData for MISSION_WRITE_PARTIAL_LIST_DATA {
25000 type Message = MavMessage;
25001 const ID: u32 = 38u32;
25002 const NAME: &'static str = "MISSION_WRITE_PARTIAL_LIST";
25003 const EXTRA_CRC: u8 = 9u8;
25004 const ENCODED_LEN: usize = 7usize;
25005 fn deser(
25006 _version: MavlinkVersion,
25007 __input: &[u8],
25008 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25009 let avail_len = __input.len();
25010 let mut payload_buf = [0; Self::ENCODED_LEN];
25011 let mut buf = if avail_len < Self::ENCODED_LEN {
25012 payload_buf[0..avail_len].copy_from_slice(__input);
25013 Bytes::new(&payload_buf)
25014 } else {
25015 Bytes::new(__input)
25016 };
25017 let mut __struct = Self::default();
25018 __struct.start_index = buf.get_i16_le();
25019 __struct.end_index = buf.get_i16_le();
25020 __struct.target_system = buf.get_u8();
25021 __struct.target_component = buf.get_u8();
25022 let tmp = buf.get_u8();
25023 __struct.mission_type =
25024 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25025 enum_type: "MavMissionType",
25026 value: tmp as u32,
25027 })?;
25028 Ok(__struct)
25029 }
25030 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25031 let mut __tmp = BytesMut::new(bytes);
25032 #[allow(clippy::absurd_extreme_comparisons)]
25033 #[allow(unused_comparisons)]
25034 if __tmp.remaining() < Self::ENCODED_LEN {
25035 panic!(
25036 "buffer is too small (need {} bytes, but got {})",
25037 Self::ENCODED_LEN,
25038 __tmp.remaining(),
25039 )
25040 }
25041 __tmp.put_i16_le(self.start_index);
25042 __tmp.put_i16_le(self.end_index);
25043 __tmp.put_u8(self.target_system);
25044 __tmp.put_u8(self.target_component);
25045 __tmp.put_u8(self.mission_type as u8);
25046 if matches!(version, MavlinkVersion::V2) {
25047 let len = __tmp.len();
25048 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25049 } else {
25050 __tmp.len()
25051 }
25052 }
25053}
25054#[doc = "id: 74"]
25055#[doc = "Metrics typically displayed on a HUD for fixed wing aircraft."]
25056#[derive(Debug, Clone, PartialEq)]
25057#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25058#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25059pub struct VFR_HUD_DATA {
25060 #[doc = "Vehicle speed in form appropriate for vehicle type. For standard aircraft this is typically calibrated airspeed (CAS) or indicated airspeed (IAS) - either of which can be used by a pilot to estimate stall speed."]
25061 pub airspeed: f32,
25062 #[doc = "Current ground speed."]
25063 pub groundspeed: f32,
25064 #[doc = "Current altitude (MSL)."]
25065 pub alt: f32,
25066 #[doc = "Current climb rate."]
25067 pub climb: f32,
25068 #[doc = "Current heading in compass units (0-360, 0=north)."]
25069 pub heading: i16,
25070 #[doc = "Current throttle setting (0 to 100)."]
25071 pub throttle: u16,
25072}
25073impl VFR_HUD_DATA {
25074 pub const ENCODED_LEN: usize = 20usize;
25075 pub const DEFAULT: Self = Self {
25076 airspeed: 0.0_f32,
25077 groundspeed: 0.0_f32,
25078 alt: 0.0_f32,
25079 climb: 0.0_f32,
25080 heading: 0_i16,
25081 throttle: 0_u16,
25082 };
25083 #[cfg(feature = "arbitrary")]
25084 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25085 use arbitrary::{Arbitrary, Unstructured};
25086 let mut buf = [0u8; 1024];
25087 rng.fill_bytes(&mut buf);
25088 let mut unstructured = Unstructured::new(&buf);
25089 Self::arbitrary(&mut unstructured).unwrap_or_default()
25090 }
25091}
25092impl Default for VFR_HUD_DATA {
25093 fn default() -> Self {
25094 Self::DEFAULT.clone()
25095 }
25096}
25097impl MessageData for VFR_HUD_DATA {
25098 type Message = MavMessage;
25099 const ID: u32 = 74u32;
25100 const NAME: &'static str = "VFR_HUD";
25101 const EXTRA_CRC: u8 = 20u8;
25102 const ENCODED_LEN: usize = 20usize;
25103 fn deser(
25104 _version: MavlinkVersion,
25105 __input: &[u8],
25106 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25107 let avail_len = __input.len();
25108 let mut payload_buf = [0; Self::ENCODED_LEN];
25109 let mut buf = if avail_len < Self::ENCODED_LEN {
25110 payload_buf[0..avail_len].copy_from_slice(__input);
25111 Bytes::new(&payload_buf)
25112 } else {
25113 Bytes::new(__input)
25114 };
25115 let mut __struct = Self::default();
25116 __struct.airspeed = buf.get_f32_le();
25117 __struct.groundspeed = buf.get_f32_le();
25118 __struct.alt = buf.get_f32_le();
25119 __struct.climb = buf.get_f32_le();
25120 __struct.heading = buf.get_i16_le();
25121 __struct.throttle = buf.get_u16_le();
25122 Ok(__struct)
25123 }
25124 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25125 let mut __tmp = BytesMut::new(bytes);
25126 #[allow(clippy::absurd_extreme_comparisons)]
25127 #[allow(unused_comparisons)]
25128 if __tmp.remaining() < Self::ENCODED_LEN {
25129 panic!(
25130 "buffer is too small (need {} bytes, but got {})",
25131 Self::ENCODED_LEN,
25132 __tmp.remaining(),
25133 )
25134 }
25135 __tmp.put_f32_le(self.airspeed);
25136 __tmp.put_f32_le(self.groundspeed);
25137 __tmp.put_f32_le(self.alt);
25138 __tmp.put_f32_le(self.climb);
25139 __tmp.put_i16_le(self.heading);
25140 __tmp.put_u16_le(self.throttle);
25141 if matches!(version, MavlinkVersion::V2) {
25142 let len = __tmp.len();
25143 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25144 } else {
25145 __tmp.len()
25146 }
25147 }
25148}
25149#[doc = "id: 85"]
25150#[doc = "Reports the current commanded vehicle position, velocity, and acceleration as specified by the autopilot. This should match the commands sent in SET_POSITION_TARGET_LOCAL_NED if the vehicle is being controlled this way."]
25151#[derive(Debug, Clone, PartialEq)]
25152#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25153#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25154pub struct POSITION_TARGET_LOCAL_NED_DATA {
25155 #[doc = "Timestamp (time since system boot)."]
25156 pub time_boot_ms: u32,
25157 #[doc = "X Position in NED frame"]
25158 pub x: f32,
25159 #[doc = "Y Position in NED frame"]
25160 pub y: f32,
25161 #[doc = "Z Position in NED frame (note, altitude is negative in NED)"]
25162 pub z: f32,
25163 #[doc = "X velocity in NED frame"]
25164 pub vx: f32,
25165 #[doc = "Y velocity in NED frame"]
25166 pub vy: f32,
25167 #[doc = "Z velocity in NED frame"]
25168 pub vz: f32,
25169 #[doc = "X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
25170 pub afx: f32,
25171 #[doc = "Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
25172 pub afy: f32,
25173 #[doc = "Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N"]
25174 pub afz: f32,
25175 #[doc = "yaw setpoint"]
25176 pub yaw: f32,
25177 #[doc = "yaw rate setpoint"]
25178 pub yaw_rate: f32,
25179 #[doc = "Bitmap to indicate which dimensions should be ignored by the vehicle."]
25180 pub type_mask: PositionTargetTypemask,
25181 #[doc = "Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9"]
25182 pub coordinate_frame: MavFrame,
25183}
25184impl POSITION_TARGET_LOCAL_NED_DATA {
25185 pub const ENCODED_LEN: usize = 51usize;
25186 pub const DEFAULT: Self = Self {
25187 time_boot_ms: 0_u32,
25188 x: 0.0_f32,
25189 y: 0.0_f32,
25190 z: 0.0_f32,
25191 vx: 0.0_f32,
25192 vy: 0.0_f32,
25193 vz: 0.0_f32,
25194 afx: 0.0_f32,
25195 afy: 0.0_f32,
25196 afz: 0.0_f32,
25197 yaw: 0.0_f32,
25198 yaw_rate: 0.0_f32,
25199 type_mask: PositionTargetTypemask::DEFAULT,
25200 coordinate_frame: MavFrame::DEFAULT,
25201 };
25202 #[cfg(feature = "arbitrary")]
25203 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25204 use arbitrary::{Arbitrary, Unstructured};
25205 let mut buf = [0u8; 1024];
25206 rng.fill_bytes(&mut buf);
25207 let mut unstructured = Unstructured::new(&buf);
25208 Self::arbitrary(&mut unstructured).unwrap_or_default()
25209 }
25210}
25211impl Default for POSITION_TARGET_LOCAL_NED_DATA {
25212 fn default() -> Self {
25213 Self::DEFAULT.clone()
25214 }
25215}
25216impl MessageData for POSITION_TARGET_LOCAL_NED_DATA {
25217 type Message = MavMessage;
25218 const ID: u32 = 85u32;
25219 const NAME: &'static str = "POSITION_TARGET_LOCAL_NED";
25220 const EXTRA_CRC: u8 = 140u8;
25221 const ENCODED_LEN: usize = 51usize;
25222 fn deser(
25223 _version: MavlinkVersion,
25224 __input: &[u8],
25225 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25226 let avail_len = __input.len();
25227 let mut payload_buf = [0; Self::ENCODED_LEN];
25228 let mut buf = if avail_len < Self::ENCODED_LEN {
25229 payload_buf[0..avail_len].copy_from_slice(__input);
25230 Bytes::new(&payload_buf)
25231 } else {
25232 Bytes::new(__input)
25233 };
25234 let mut __struct = Self::default();
25235 __struct.time_boot_ms = buf.get_u32_le();
25236 __struct.x = buf.get_f32_le();
25237 __struct.y = buf.get_f32_le();
25238 __struct.z = buf.get_f32_le();
25239 __struct.vx = buf.get_f32_le();
25240 __struct.vy = buf.get_f32_le();
25241 __struct.vz = buf.get_f32_le();
25242 __struct.afx = buf.get_f32_le();
25243 __struct.afy = buf.get_f32_le();
25244 __struct.afz = buf.get_f32_le();
25245 __struct.yaw = buf.get_f32_le();
25246 __struct.yaw_rate = buf.get_f32_le();
25247 let tmp = buf.get_u16_le();
25248 __struct.type_mask = PositionTargetTypemask::from_bits(
25249 tmp & PositionTargetTypemask::all().bits(),
25250 )
25251 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
25252 flag_type: "PositionTargetTypemask",
25253 value: tmp as u32,
25254 })?;
25255 let tmp = buf.get_u8();
25256 __struct.coordinate_frame =
25257 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25258 enum_type: "MavFrame",
25259 value: tmp as u32,
25260 })?;
25261 Ok(__struct)
25262 }
25263 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25264 let mut __tmp = BytesMut::new(bytes);
25265 #[allow(clippy::absurd_extreme_comparisons)]
25266 #[allow(unused_comparisons)]
25267 if __tmp.remaining() < Self::ENCODED_LEN {
25268 panic!(
25269 "buffer is too small (need {} bytes, but got {})",
25270 Self::ENCODED_LEN,
25271 __tmp.remaining(),
25272 )
25273 }
25274 __tmp.put_u32_le(self.time_boot_ms);
25275 __tmp.put_f32_le(self.x);
25276 __tmp.put_f32_le(self.y);
25277 __tmp.put_f32_le(self.z);
25278 __tmp.put_f32_le(self.vx);
25279 __tmp.put_f32_le(self.vy);
25280 __tmp.put_f32_le(self.vz);
25281 __tmp.put_f32_le(self.afx);
25282 __tmp.put_f32_le(self.afy);
25283 __tmp.put_f32_le(self.afz);
25284 __tmp.put_f32_le(self.yaw);
25285 __tmp.put_f32_le(self.yaw_rate);
25286 __tmp.put_u16_le(self.type_mask.bits());
25287 __tmp.put_u8(self.coordinate_frame as u8);
25288 if matches!(version, MavlinkVersion::V2) {
25289 let len = __tmp.len();
25290 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25291 } else {
25292 __tmp.len()
25293 }
25294 }
25295}
25296#[doc = "id: 45"]
25297#[doc = "Delete all mission items at once."]
25298#[derive(Debug, Clone, PartialEq)]
25299#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25300#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25301pub struct MISSION_CLEAR_ALL_DATA {
25302 #[doc = "System ID"]
25303 pub target_system: u8,
25304 #[doc = "Component ID"]
25305 pub target_component: u8,
25306 #[doc = "Mission type."]
25307 #[cfg_attr(feature = "serde", serde(default))]
25308 pub mission_type: MavMissionType,
25309}
25310impl MISSION_CLEAR_ALL_DATA {
25311 pub const ENCODED_LEN: usize = 3usize;
25312 pub const DEFAULT: Self = Self {
25313 target_system: 0_u8,
25314 target_component: 0_u8,
25315 mission_type: MavMissionType::DEFAULT,
25316 };
25317 #[cfg(feature = "arbitrary")]
25318 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25319 use arbitrary::{Arbitrary, Unstructured};
25320 let mut buf = [0u8; 1024];
25321 rng.fill_bytes(&mut buf);
25322 let mut unstructured = Unstructured::new(&buf);
25323 Self::arbitrary(&mut unstructured).unwrap_or_default()
25324 }
25325}
25326impl Default for MISSION_CLEAR_ALL_DATA {
25327 fn default() -> Self {
25328 Self::DEFAULT.clone()
25329 }
25330}
25331impl MessageData for MISSION_CLEAR_ALL_DATA {
25332 type Message = MavMessage;
25333 const ID: u32 = 45u32;
25334 const NAME: &'static str = "MISSION_CLEAR_ALL";
25335 const EXTRA_CRC: u8 = 232u8;
25336 const ENCODED_LEN: usize = 3usize;
25337 fn deser(
25338 _version: MavlinkVersion,
25339 __input: &[u8],
25340 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25341 let avail_len = __input.len();
25342 let mut payload_buf = [0; Self::ENCODED_LEN];
25343 let mut buf = if avail_len < Self::ENCODED_LEN {
25344 payload_buf[0..avail_len].copy_from_slice(__input);
25345 Bytes::new(&payload_buf)
25346 } else {
25347 Bytes::new(__input)
25348 };
25349 let mut __struct = Self::default();
25350 __struct.target_system = buf.get_u8();
25351 __struct.target_component = buf.get_u8();
25352 let tmp = buf.get_u8();
25353 __struct.mission_type =
25354 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25355 enum_type: "MavMissionType",
25356 value: tmp as u32,
25357 })?;
25358 Ok(__struct)
25359 }
25360 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25361 let mut __tmp = BytesMut::new(bytes);
25362 #[allow(clippy::absurd_extreme_comparisons)]
25363 #[allow(unused_comparisons)]
25364 if __tmp.remaining() < Self::ENCODED_LEN {
25365 panic!(
25366 "buffer is too small (need {} bytes, but got {})",
25367 Self::ENCODED_LEN,
25368 __tmp.remaining(),
25369 )
25370 }
25371 __tmp.put_u8(self.target_system);
25372 __tmp.put_u8(self.target_component);
25373 __tmp.put_u8(self.mission_type as u8);
25374 if matches!(version, MavlinkVersion::V2) {
25375 let len = __tmp.len();
25376 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25377 } else {
25378 __tmp.len()
25379 }
25380 }
25381}
25382#[doc = "id: 69"]
25383#[doc = "This message provides an API for manually controlling the vehicle using standard joystick axes nomenclature, along with a joystick-like input device. Unused axes can be disabled and buttons states are transmitted as individual on/off bits of a bitmask."]
25384#[derive(Debug, Clone, PartialEq)]
25385#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25386#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25387pub struct MANUAL_CONTROL_DATA {
25388 #[doc = "X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle."]
25389 pub x: i16,
25390 #[doc = "Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle."]
25391 pub y: i16,
25392 #[doc = "Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle. Positive values are positive thrust, negative values are negative thrust."]
25393 pub z: i16,
25394 #[doc = "R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle."]
25395 pub r: i16,
25396 #[doc = "A bitfield corresponding to the joystick buttons' 0-15 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1."]
25397 pub buttons: u16,
25398 #[doc = "The system to be controlled."]
25399 pub target: u8,
25400 #[doc = "A bitfield corresponding to the joystick buttons' 16-31 current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 16."]
25401 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25402 pub buttons2: u16,
25403 #[doc = "Set bits to 1 to indicate which of the following extension fields contain valid data: bit 0: pitch, bit 1: roll, bit 2: aux1, bit 3: aux2, bit 4: aux3, bit 5: aux4, bit 6: aux5, bit 7: aux6"]
25404 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25405 pub enabled_extensions: u8,
25406 #[doc = "Pitch-only-axis, normalized to the range [-1000,1000]. Generally corresponds to pitch on vehicles with additional degrees of freedom. Valid if bit 0 of enabled_extensions field is set. Set to 0 if invalid."]
25407 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25408 pub s: i16,
25409 #[doc = "Roll-only-axis, normalized to the range [-1000,1000]. Generally corresponds to roll on vehicles with additional degrees of freedom. Valid if bit 1 of enabled_extensions field is set. Set to 0 if invalid."]
25410 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25411 pub t: i16,
25412 #[doc = "Aux continuous input field 1. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 2 of enabled_extensions field is set. 0 if bit 2 is unset."]
25413 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25414 pub aux1: i16,
25415 #[doc = "Aux continuous input field 2. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 3 of enabled_extensions field is set. 0 if bit 3 is unset."]
25416 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25417 pub aux2: i16,
25418 #[doc = "Aux continuous input field 3. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 4 of enabled_extensions field is set. 0 if bit 4 is unset."]
25419 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25420 pub aux3: i16,
25421 #[doc = "Aux continuous input field 4. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 5 of enabled_extensions field is set. 0 if bit 5 is unset."]
25422 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25423 pub aux4: i16,
25424 #[doc = "Aux continuous input field 5. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 6 of enabled_extensions field is set. 0 if bit 6 is unset."]
25425 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25426 pub aux5: i16,
25427 #[doc = "Aux continuous input field 6. Normalized in the range [-1000,1000]. Purpose defined by recipient. Valid data if bit 7 of enabled_extensions field is set. 0 if bit 7 is unset."]
25428 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25429 pub aux6: i16,
25430}
25431impl MANUAL_CONTROL_DATA {
25432 pub const ENCODED_LEN: usize = 30usize;
25433 pub const DEFAULT: Self = Self {
25434 x: 0_i16,
25435 y: 0_i16,
25436 z: 0_i16,
25437 r: 0_i16,
25438 buttons: 0_u16,
25439 target: 0_u8,
25440 buttons2: 0_u16,
25441 enabled_extensions: 0_u8,
25442 s: 0_i16,
25443 t: 0_i16,
25444 aux1: 0_i16,
25445 aux2: 0_i16,
25446 aux3: 0_i16,
25447 aux4: 0_i16,
25448 aux5: 0_i16,
25449 aux6: 0_i16,
25450 };
25451 #[cfg(feature = "arbitrary")]
25452 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25453 use arbitrary::{Arbitrary, Unstructured};
25454 let mut buf = [0u8; 1024];
25455 rng.fill_bytes(&mut buf);
25456 let mut unstructured = Unstructured::new(&buf);
25457 Self::arbitrary(&mut unstructured).unwrap_or_default()
25458 }
25459}
25460impl Default for MANUAL_CONTROL_DATA {
25461 fn default() -> Self {
25462 Self::DEFAULT.clone()
25463 }
25464}
25465impl MessageData for MANUAL_CONTROL_DATA {
25466 type Message = MavMessage;
25467 const ID: u32 = 69u32;
25468 const NAME: &'static str = "MANUAL_CONTROL";
25469 const EXTRA_CRC: u8 = 243u8;
25470 const ENCODED_LEN: usize = 30usize;
25471 fn deser(
25472 _version: MavlinkVersion,
25473 __input: &[u8],
25474 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25475 let avail_len = __input.len();
25476 let mut payload_buf = [0; Self::ENCODED_LEN];
25477 let mut buf = if avail_len < Self::ENCODED_LEN {
25478 payload_buf[0..avail_len].copy_from_slice(__input);
25479 Bytes::new(&payload_buf)
25480 } else {
25481 Bytes::new(__input)
25482 };
25483 let mut __struct = Self::default();
25484 __struct.x = buf.get_i16_le();
25485 __struct.y = buf.get_i16_le();
25486 __struct.z = buf.get_i16_le();
25487 __struct.r = buf.get_i16_le();
25488 __struct.buttons = buf.get_u16_le();
25489 __struct.target = buf.get_u8();
25490 __struct.buttons2 = buf.get_u16_le();
25491 __struct.enabled_extensions = buf.get_u8();
25492 __struct.s = buf.get_i16_le();
25493 __struct.t = buf.get_i16_le();
25494 __struct.aux1 = buf.get_i16_le();
25495 __struct.aux2 = buf.get_i16_le();
25496 __struct.aux3 = buf.get_i16_le();
25497 __struct.aux4 = buf.get_i16_le();
25498 __struct.aux5 = buf.get_i16_le();
25499 __struct.aux6 = buf.get_i16_le();
25500 Ok(__struct)
25501 }
25502 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25503 let mut __tmp = BytesMut::new(bytes);
25504 #[allow(clippy::absurd_extreme_comparisons)]
25505 #[allow(unused_comparisons)]
25506 if __tmp.remaining() < Self::ENCODED_LEN {
25507 panic!(
25508 "buffer is too small (need {} bytes, but got {})",
25509 Self::ENCODED_LEN,
25510 __tmp.remaining(),
25511 )
25512 }
25513 __tmp.put_i16_le(self.x);
25514 __tmp.put_i16_le(self.y);
25515 __tmp.put_i16_le(self.z);
25516 __tmp.put_i16_le(self.r);
25517 __tmp.put_u16_le(self.buttons);
25518 __tmp.put_u8(self.target);
25519 __tmp.put_u16_le(self.buttons2);
25520 __tmp.put_u8(self.enabled_extensions);
25521 __tmp.put_i16_le(self.s);
25522 __tmp.put_i16_le(self.t);
25523 __tmp.put_i16_le(self.aux1);
25524 __tmp.put_i16_le(self.aux2);
25525 __tmp.put_i16_le(self.aux3);
25526 __tmp.put_i16_le(self.aux4);
25527 __tmp.put_i16_le(self.aux5);
25528 __tmp.put_i16_le(self.aux6);
25529 if matches!(version, MavlinkVersion::V2) {
25530 let len = __tmp.len();
25531 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25532 } else {
25533 __tmp.len()
25534 }
25535 }
25536}
25537#[doc = "id: 435"]
25538#[doc = "Information about a flight mode. The message can be enumerated to get information for all modes, or requested for a particular mode, using MAV_CMD_REQUEST_MESSAGE. Specify 0 in param2 to request that the message is emitted for all available modes or the specific index for just one mode. The modes must be available/settable for the current vehicle/frame type. Each mode should only be emitted once (even if it is both standard and custom). Note that the current mode should be emitted in CURRENT_MODE, and that if the mode list can change then AVAILABLE_MODES_MONITOR must be emitted on first change and subsequently streamed. See <https://mavlink.io/en/services/standard_modes.html>."]
25539#[derive(Debug, Clone, PartialEq)]
25540#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25541#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25542pub struct AVAILABLE_MODES_DATA {
25543 #[doc = "A bitfield for use for autopilot-specific flags"]
25544 pub custom_mode: u32,
25545 #[doc = "Mode properties."]
25546 pub properties: MavModeProperty,
25547 #[doc = "The total number of available modes for the current vehicle type."]
25548 pub number_modes: u8,
25549 #[doc = "The current mode index within number_modes, indexed from 1. The index is not guaranteed to be persistent, and may change between reboots or if the set of modes change."]
25550 pub mode_index: u8,
25551 #[doc = "Standard mode."]
25552 pub standard_mode: MavStandardMode,
25553 #[doc = "Name of custom mode, with null termination character. Should be omitted for standard modes."]
25554 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25555 pub mode_name: [u8; 35],
25556}
25557impl AVAILABLE_MODES_DATA {
25558 pub const ENCODED_LEN: usize = 46usize;
25559 pub const DEFAULT: Self = Self {
25560 custom_mode: 0_u32,
25561 properties: MavModeProperty::DEFAULT,
25562 number_modes: 0_u8,
25563 mode_index: 0_u8,
25564 standard_mode: MavStandardMode::DEFAULT,
25565 mode_name: [0_u8; 35usize],
25566 };
25567 #[cfg(feature = "arbitrary")]
25568 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25569 use arbitrary::{Arbitrary, Unstructured};
25570 let mut buf = [0u8; 1024];
25571 rng.fill_bytes(&mut buf);
25572 let mut unstructured = Unstructured::new(&buf);
25573 Self::arbitrary(&mut unstructured).unwrap_or_default()
25574 }
25575}
25576impl Default for AVAILABLE_MODES_DATA {
25577 fn default() -> Self {
25578 Self::DEFAULT.clone()
25579 }
25580}
25581impl MessageData for AVAILABLE_MODES_DATA {
25582 type Message = MavMessage;
25583 const ID: u32 = 435u32;
25584 const NAME: &'static str = "AVAILABLE_MODES";
25585 const EXTRA_CRC: u8 = 134u8;
25586 const ENCODED_LEN: usize = 46usize;
25587 fn deser(
25588 _version: MavlinkVersion,
25589 __input: &[u8],
25590 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25591 let avail_len = __input.len();
25592 let mut payload_buf = [0; Self::ENCODED_LEN];
25593 let mut buf = if avail_len < Self::ENCODED_LEN {
25594 payload_buf[0..avail_len].copy_from_slice(__input);
25595 Bytes::new(&payload_buf)
25596 } else {
25597 Bytes::new(__input)
25598 };
25599 let mut __struct = Self::default();
25600 __struct.custom_mode = buf.get_u32_le();
25601 let tmp = buf.get_u32_le();
25602 __struct.properties = MavModeProperty::from_bits(tmp & MavModeProperty::all().bits())
25603 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
25604 flag_type: "MavModeProperty",
25605 value: tmp as u32,
25606 })?;
25607 __struct.number_modes = buf.get_u8();
25608 __struct.mode_index = buf.get_u8();
25609 let tmp = buf.get_u8();
25610 __struct.standard_mode =
25611 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25612 enum_type: "MavStandardMode",
25613 value: tmp as u32,
25614 })?;
25615 for v in &mut __struct.mode_name {
25616 let val = buf.get_u8();
25617 *v = val;
25618 }
25619 Ok(__struct)
25620 }
25621 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25622 let mut __tmp = BytesMut::new(bytes);
25623 #[allow(clippy::absurd_extreme_comparisons)]
25624 #[allow(unused_comparisons)]
25625 if __tmp.remaining() < Self::ENCODED_LEN {
25626 panic!(
25627 "buffer is too small (need {} bytes, but got {})",
25628 Self::ENCODED_LEN,
25629 __tmp.remaining(),
25630 )
25631 }
25632 __tmp.put_u32_le(self.custom_mode);
25633 __tmp.put_u32_le(self.properties.bits());
25634 __tmp.put_u8(self.number_modes);
25635 __tmp.put_u8(self.mode_index);
25636 __tmp.put_u8(self.standard_mode as u8);
25637 for val in &self.mode_name {
25638 __tmp.put_u8(*val);
25639 }
25640 if matches!(version, MavlinkVersion::V2) {
25641 let len = __tmp.len();
25642 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25643 } else {
25644 __tmp.len()
25645 }
25646 }
25647}
25648#[doc = "id: 380"]
25649#[doc = "Time/duration estimates for various events and actions given the current vehicle state and position."]
25650#[derive(Debug, Clone, PartialEq)]
25651#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25652#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25653pub struct TIME_ESTIMATE_TO_TARGET_DATA {
25654 #[doc = "Estimated time to complete the vehicle's configured \"safe return\" action from its current position (e.g. RTL, Smart RTL, etc.). -1 indicates that the vehicle is landed, or that no time estimate available."]
25655 pub safe_return: i32,
25656 #[doc = "Estimated time for vehicle to complete the LAND action from its current position. -1 indicates that the vehicle is landed, or that no time estimate available."]
25657 pub land: i32,
25658 #[doc = "Estimated time for reaching/completing the currently active mission item. -1 means no time estimate available."]
25659 pub mission_next_item: i32,
25660 #[doc = "Estimated time for completing the current mission. -1 means no mission active and/or no estimate available."]
25661 pub mission_end: i32,
25662 #[doc = "Estimated time for completing the current commanded action (i.e. Go To, Takeoff, Land, etc.). -1 means no action active and/or no estimate available."]
25663 pub commanded_action: i32,
25664}
25665impl TIME_ESTIMATE_TO_TARGET_DATA {
25666 pub const ENCODED_LEN: usize = 20usize;
25667 pub const DEFAULT: Self = Self {
25668 safe_return: 0_i32,
25669 land: 0_i32,
25670 mission_next_item: 0_i32,
25671 mission_end: 0_i32,
25672 commanded_action: 0_i32,
25673 };
25674 #[cfg(feature = "arbitrary")]
25675 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25676 use arbitrary::{Arbitrary, Unstructured};
25677 let mut buf = [0u8; 1024];
25678 rng.fill_bytes(&mut buf);
25679 let mut unstructured = Unstructured::new(&buf);
25680 Self::arbitrary(&mut unstructured).unwrap_or_default()
25681 }
25682}
25683impl Default for TIME_ESTIMATE_TO_TARGET_DATA {
25684 fn default() -> Self {
25685 Self::DEFAULT.clone()
25686 }
25687}
25688impl MessageData for TIME_ESTIMATE_TO_TARGET_DATA {
25689 type Message = MavMessage;
25690 const ID: u32 = 380u32;
25691 const NAME: &'static str = "TIME_ESTIMATE_TO_TARGET";
25692 const EXTRA_CRC: u8 = 232u8;
25693 const ENCODED_LEN: usize = 20usize;
25694 fn deser(
25695 _version: MavlinkVersion,
25696 __input: &[u8],
25697 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25698 let avail_len = __input.len();
25699 let mut payload_buf = [0; Self::ENCODED_LEN];
25700 let mut buf = if avail_len < Self::ENCODED_LEN {
25701 payload_buf[0..avail_len].copy_from_slice(__input);
25702 Bytes::new(&payload_buf)
25703 } else {
25704 Bytes::new(__input)
25705 };
25706 let mut __struct = Self::default();
25707 __struct.safe_return = buf.get_i32_le();
25708 __struct.land = buf.get_i32_le();
25709 __struct.mission_next_item = buf.get_i32_le();
25710 __struct.mission_end = buf.get_i32_le();
25711 __struct.commanded_action = buf.get_i32_le();
25712 Ok(__struct)
25713 }
25714 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25715 let mut __tmp = BytesMut::new(bytes);
25716 #[allow(clippy::absurd_extreme_comparisons)]
25717 #[allow(unused_comparisons)]
25718 if __tmp.remaining() < Self::ENCODED_LEN {
25719 panic!(
25720 "buffer is too small (need {} bytes, but got {})",
25721 Self::ENCODED_LEN,
25722 __tmp.remaining(),
25723 )
25724 }
25725 __tmp.put_i32_le(self.safe_return);
25726 __tmp.put_i32_le(self.land);
25727 __tmp.put_i32_le(self.mission_next_item);
25728 __tmp.put_i32_le(self.mission_end);
25729 __tmp.put_i32_le(self.commanded_action);
25730 if matches!(version, MavlinkVersion::V2) {
25731 let len = __tmp.len();
25732 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25733 } else {
25734 __tmp.len()
25735 }
25736 }
25737}
25738#[doc = "id: 24"]
25739#[doc = "The global position, as returned by the Global Positioning System (GPS). This is NOT the global position estimate of the system, but rather a RAW sensor value. See message GLOBAL_POSITION_INT for the global position estimate."]
25740#[derive(Debug, Clone, PartialEq)]
25741#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25742#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25743pub struct GPS_RAW_INT_DATA {
25744 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
25745 pub time_usec: u64,
25746 #[doc = "Latitude (WGS84, EGM96 ellipsoid)"]
25747 pub lat: i32,
25748 #[doc = "Longitude (WGS84, EGM96 ellipsoid)"]
25749 pub lon: i32,
25750 #[doc = "Altitude (MSL). Positive for up. Note that virtually all GPS modules provide the MSL altitude in addition to the WGS84 altitude."]
25751 pub alt: i32,
25752 #[doc = "GPS HDOP horizontal dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
25753 pub eph: u16,
25754 #[doc = "GPS VDOP vertical dilution of position (unitless * 100). If unknown, set to: UINT16_MAX"]
25755 pub epv: u16,
25756 #[doc = "GPS ground speed. If unknown, set to: UINT16_MAX"]
25757 pub vel: u16,
25758 #[doc = "Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX"]
25759 pub cog: u16,
25760 #[doc = "GPS fix type."]
25761 pub fix_type: GpsFixType,
25762 #[doc = "Number of satellites visible. If unknown, set to UINT8_MAX"]
25763 pub satellites_visible: u8,
25764 #[doc = "Altitude (above WGS84, EGM96 ellipsoid). Positive for up."]
25765 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25766 pub alt_ellipsoid: i32,
25767 #[doc = "Position uncertainty."]
25768 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25769 pub h_acc: u32,
25770 #[doc = "Altitude uncertainty."]
25771 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25772 pub v_acc: u32,
25773 #[doc = "Speed uncertainty."]
25774 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25775 pub vel_acc: u32,
25776 #[doc = "Heading / track uncertainty"]
25777 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25778 pub hdg_acc: u32,
25779 #[doc = "Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use UINT16_MAX if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north."]
25780 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25781 pub yaw: u16,
25782}
25783impl GPS_RAW_INT_DATA {
25784 pub const ENCODED_LEN: usize = 52usize;
25785 pub const DEFAULT: Self = Self {
25786 time_usec: 0_u64,
25787 lat: 0_i32,
25788 lon: 0_i32,
25789 alt: 0_i32,
25790 eph: 0_u16,
25791 epv: 0_u16,
25792 vel: 0_u16,
25793 cog: 0_u16,
25794 fix_type: GpsFixType::DEFAULT,
25795 satellites_visible: 0_u8,
25796 alt_ellipsoid: 0_i32,
25797 h_acc: 0_u32,
25798 v_acc: 0_u32,
25799 vel_acc: 0_u32,
25800 hdg_acc: 0_u32,
25801 yaw: 0_u16,
25802 };
25803 #[cfg(feature = "arbitrary")]
25804 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25805 use arbitrary::{Arbitrary, Unstructured};
25806 let mut buf = [0u8; 1024];
25807 rng.fill_bytes(&mut buf);
25808 let mut unstructured = Unstructured::new(&buf);
25809 Self::arbitrary(&mut unstructured).unwrap_or_default()
25810 }
25811}
25812impl Default for GPS_RAW_INT_DATA {
25813 fn default() -> Self {
25814 Self::DEFAULT.clone()
25815 }
25816}
25817impl MessageData for GPS_RAW_INT_DATA {
25818 type Message = MavMessage;
25819 const ID: u32 = 24u32;
25820 const NAME: &'static str = "GPS_RAW_INT";
25821 const EXTRA_CRC: u8 = 24u8;
25822 const ENCODED_LEN: usize = 52usize;
25823 fn deser(
25824 _version: MavlinkVersion,
25825 __input: &[u8],
25826 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25827 let avail_len = __input.len();
25828 let mut payload_buf = [0; Self::ENCODED_LEN];
25829 let mut buf = if avail_len < Self::ENCODED_LEN {
25830 payload_buf[0..avail_len].copy_from_slice(__input);
25831 Bytes::new(&payload_buf)
25832 } else {
25833 Bytes::new(__input)
25834 };
25835 let mut __struct = Self::default();
25836 __struct.time_usec = buf.get_u64_le();
25837 __struct.lat = buf.get_i32_le();
25838 __struct.lon = buf.get_i32_le();
25839 __struct.alt = buf.get_i32_le();
25840 __struct.eph = buf.get_u16_le();
25841 __struct.epv = buf.get_u16_le();
25842 __struct.vel = buf.get_u16_le();
25843 __struct.cog = buf.get_u16_le();
25844 let tmp = buf.get_u8();
25845 __struct.fix_type =
25846 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
25847 enum_type: "GpsFixType",
25848 value: tmp as u32,
25849 })?;
25850 __struct.satellites_visible = buf.get_u8();
25851 __struct.alt_ellipsoid = buf.get_i32_le();
25852 __struct.h_acc = buf.get_u32_le();
25853 __struct.v_acc = buf.get_u32_le();
25854 __struct.vel_acc = buf.get_u32_le();
25855 __struct.hdg_acc = buf.get_u32_le();
25856 __struct.yaw = buf.get_u16_le();
25857 Ok(__struct)
25858 }
25859 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25860 let mut __tmp = BytesMut::new(bytes);
25861 #[allow(clippy::absurd_extreme_comparisons)]
25862 #[allow(unused_comparisons)]
25863 if __tmp.remaining() < Self::ENCODED_LEN {
25864 panic!(
25865 "buffer is too small (need {} bytes, but got {})",
25866 Self::ENCODED_LEN,
25867 __tmp.remaining(),
25868 )
25869 }
25870 __tmp.put_u64_le(self.time_usec);
25871 __tmp.put_i32_le(self.lat);
25872 __tmp.put_i32_le(self.lon);
25873 __tmp.put_i32_le(self.alt);
25874 __tmp.put_u16_le(self.eph);
25875 __tmp.put_u16_le(self.epv);
25876 __tmp.put_u16_le(self.vel);
25877 __tmp.put_u16_le(self.cog);
25878 __tmp.put_u8(self.fix_type as u8);
25879 __tmp.put_u8(self.satellites_visible);
25880 __tmp.put_i32_le(self.alt_ellipsoid);
25881 __tmp.put_u32_le(self.h_acc);
25882 __tmp.put_u32_le(self.v_acc);
25883 __tmp.put_u32_le(self.vel_acc);
25884 __tmp.put_u32_le(self.hdg_acc);
25885 __tmp.put_u16_le(self.yaw);
25886 if matches!(version, MavlinkVersion::V2) {
25887 let len = __tmp.len();
25888 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25889 } else {
25890 __tmp.len()
25891 }
25892 }
25893}
25894#[doc = "id: 10003"]
25895#[doc = "Transceiver heartbeat with health report (updated every 10s)."]
25896#[derive(Debug, Clone, PartialEq)]
25897#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25898#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25899pub struct UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
25900 #[doc = "ADS-B transponder messages"]
25901 pub rfHealth: UavionixAdsbRfHealth,
25902}
25903impl UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
25904 pub const ENCODED_LEN: usize = 1usize;
25905 pub const DEFAULT: Self = Self {
25906 rfHealth: UavionixAdsbRfHealth::DEFAULT,
25907 };
25908 #[cfg(feature = "arbitrary")]
25909 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
25910 use arbitrary::{Arbitrary, Unstructured};
25911 let mut buf = [0u8; 1024];
25912 rng.fill_bytes(&mut buf);
25913 let mut unstructured = Unstructured::new(&buf);
25914 Self::arbitrary(&mut unstructured).unwrap_or_default()
25915 }
25916}
25917impl Default for UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
25918 fn default() -> Self {
25919 Self::DEFAULT.clone()
25920 }
25921}
25922impl MessageData for UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA {
25923 type Message = MavMessage;
25924 const ID: u32 = 10003u32;
25925 const NAME: &'static str = "UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT";
25926 const EXTRA_CRC: u8 = 4u8;
25927 const ENCODED_LEN: usize = 1usize;
25928 fn deser(
25929 _version: MavlinkVersion,
25930 __input: &[u8],
25931 ) -> Result<Self, ::mavlink_core::error::ParserError> {
25932 let avail_len = __input.len();
25933 let mut payload_buf = [0; Self::ENCODED_LEN];
25934 let mut buf = if avail_len < Self::ENCODED_LEN {
25935 payload_buf[0..avail_len].copy_from_slice(__input);
25936 Bytes::new(&payload_buf)
25937 } else {
25938 Bytes::new(__input)
25939 };
25940 let mut __struct = Self::default();
25941 let tmp = buf.get_u8();
25942 __struct.rfHealth = UavionixAdsbRfHealth::from_bits(
25943 tmp & UavionixAdsbRfHealth::all().bits(),
25944 )
25945 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
25946 flag_type: "UavionixAdsbRfHealth",
25947 value: tmp as u32,
25948 })?;
25949 Ok(__struct)
25950 }
25951 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
25952 let mut __tmp = BytesMut::new(bytes);
25953 #[allow(clippy::absurd_extreme_comparisons)]
25954 #[allow(unused_comparisons)]
25955 if __tmp.remaining() < Self::ENCODED_LEN {
25956 panic!(
25957 "buffer is too small (need {} bytes, but got {})",
25958 Self::ENCODED_LEN,
25959 __tmp.remaining(),
25960 )
25961 }
25962 __tmp.put_u8(self.rfHealth.bits());
25963 if matches!(version, MavlinkVersion::V2) {
25964 let len = __tmp.len();
25965 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
25966 } else {
25967 __tmp.len()
25968 }
25969 }
25970}
25971#[doc = "id: 104"]
25972#[doc = "Global position estimate from a Vicon motion system source."]
25973#[derive(Debug, Clone, PartialEq)]
25974#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
25975#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
25976pub struct VICON_POSITION_ESTIMATE_DATA {
25977 #[doc = "Timestamp (UNIX time or time since system boot)"]
25978 pub usec: u64,
25979 #[doc = "Global X position"]
25980 pub x: f32,
25981 #[doc = "Global Y position"]
25982 pub y: f32,
25983 #[doc = "Global Z position"]
25984 pub z: f32,
25985 #[doc = "Roll angle"]
25986 pub roll: f32,
25987 #[doc = "Pitch angle"]
25988 pub pitch: f32,
25989 #[doc = "Yaw angle"]
25990 pub yaw: f32,
25991 #[doc = "Row-major representation of 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
25992 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
25993 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
25994 pub covariance: [f32; 21],
25995}
25996impl VICON_POSITION_ESTIMATE_DATA {
25997 pub const ENCODED_LEN: usize = 116usize;
25998 pub const DEFAULT: Self = Self {
25999 usec: 0_u64,
26000 x: 0.0_f32,
26001 y: 0.0_f32,
26002 z: 0.0_f32,
26003 roll: 0.0_f32,
26004 pitch: 0.0_f32,
26005 yaw: 0.0_f32,
26006 covariance: [0.0_f32; 21usize],
26007 };
26008 #[cfg(feature = "arbitrary")]
26009 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26010 use arbitrary::{Arbitrary, Unstructured};
26011 let mut buf = [0u8; 1024];
26012 rng.fill_bytes(&mut buf);
26013 let mut unstructured = Unstructured::new(&buf);
26014 Self::arbitrary(&mut unstructured).unwrap_or_default()
26015 }
26016}
26017impl Default for VICON_POSITION_ESTIMATE_DATA {
26018 fn default() -> Self {
26019 Self::DEFAULT.clone()
26020 }
26021}
26022impl MessageData for VICON_POSITION_ESTIMATE_DATA {
26023 type Message = MavMessage;
26024 const ID: u32 = 104u32;
26025 const NAME: &'static str = "VICON_POSITION_ESTIMATE";
26026 const EXTRA_CRC: u8 = 56u8;
26027 const ENCODED_LEN: usize = 116usize;
26028 fn deser(
26029 _version: MavlinkVersion,
26030 __input: &[u8],
26031 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26032 let avail_len = __input.len();
26033 let mut payload_buf = [0; Self::ENCODED_LEN];
26034 let mut buf = if avail_len < Self::ENCODED_LEN {
26035 payload_buf[0..avail_len].copy_from_slice(__input);
26036 Bytes::new(&payload_buf)
26037 } else {
26038 Bytes::new(__input)
26039 };
26040 let mut __struct = Self::default();
26041 __struct.usec = buf.get_u64_le();
26042 __struct.x = buf.get_f32_le();
26043 __struct.y = buf.get_f32_le();
26044 __struct.z = buf.get_f32_le();
26045 __struct.roll = buf.get_f32_le();
26046 __struct.pitch = buf.get_f32_le();
26047 __struct.yaw = buf.get_f32_le();
26048 for v in &mut __struct.covariance {
26049 let val = buf.get_f32_le();
26050 *v = val;
26051 }
26052 Ok(__struct)
26053 }
26054 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26055 let mut __tmp = BytesMut::new(bytes);
26056 #[allow(clippy::absurd_extreme_comparisons)]
26057 #[allow(unused_comparisons)]
26058 if __tmp.remaining() < Self::ENCODED_LEN {
26059 panic!(
26060 "buffer is too small (need {} bytes, but got {})",
26061 Self::ENCODED_LEN,
26062 __tmp.remaining(),
26063 )
26064 }
26065 __tmp.put_u64_le(self.usec);
26066 __tmp.put_f32_le(self.x);
26067 __tmp.put_f32_le(self.y);
26068 __tmp.put_f32_le(self.z);
26069 __tmp.put_f32_le(self.roll);
26070 __tmp.put_f32_le(self.pitch);
26071 __tmp.put_f32_le(self.yaw);
26072 for val in &self.covariance {
26073 __tmp.put_f32_le(*val);
26074 }
26075 if matches!(version, MavlinkVersion::V2) {
26076 let len = __tmp.len();
26077 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26078 } else {
26079 __tmp.len()
26080 }
26081 }
26082}
26083#[doc = "id: 137"]
26084#[doc = "Barometer readings for 2nd barometer."]
26085#[derive(Debug, Clone, PartialEq)]
26086#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26087#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26088pub struct SCALED_PRESSURE2_DATA {
26089 #[doc = "Timestamp (time since system boot)."]
26090 pub time_boot_ms: u32,
26091 #[doc = "Absolute pressure"]
26092 pub press_abs: f32,
26093 #[doc = "Differential pressure"]
26094 pub press_diff: f32,
26095 #[doc = "Absolute pressure temperature"]
26096 pub temperature: i16,
26097 #[doc = "Differential pressure temperature (0, if not available). Report values of 0 (or 1) as 1 cdegC."]
26098 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26099 pub temperature_press_diff: i16,
26100}
26101impl SCALED_PRESSURE2_DATA {
26102 pub const ENCODED_LEN: usize = 16usize;
26103 pub const DEFAULT: Self = Self {
26104 time_boot_ms: 0_u32,
26105 press_abs: 0.0_f32,
26106 press_diff: 0.0_f32,
26107 temperature: 0_i16,
26108 temperature_press_diff: 0_i16,
26109 };
26110 #[cfg(feature = "arbitrary")]
26111 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26112 use arbitrary::{Arbitrary, Unstructured};
26113 let mut buf = [0u8; 1024];
26114 rng.fill_bytes(&mut buf);
26115 let mut unstructured = Unstructured::new(&buf);
26116 Self::arbitrary(&mut unstructured).unwrap_or_default()
26117 }
26118}
26119impl Default for SCALED_PRESSURE2_DATA {
26120 fn default() -> Self {
26121 Self::DEFAULT.clone()
26122 }
26123}
26124impl MessageData for SCALED_PRESSURE2_DATA {
26125 type Message = MavMessage;
26126 const ID: u32 = 137u32;
26127 const NAME: &'static str = "SCALED_PRESSURE2";
26128 const EXTRA_CRC: u8 = 195u8;
26129 const ENCODED_LEN: usize = 16usize;
26130 fn deser(
26131 _version: MavlinkVersion,
26132 __input: &[u8],
26133 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26134 let avail_len = __input.len();
26135 let mut payload_buf = [0; Self::ENCODED_LEN];
26136 let mut buf = if avail_len < Self::ENCODED_LEN {
26137 payload_buf[0..avail_len].copy_from_slice(__input);
26138 Bytes::new(&payload_buf)
26139 } else {
26140 Bytes::new(__input)
26141 };
26142 let mut __struct = Self::default();
26143 __struct.time_boot_ms = buf.get_u32_le();
26144 __struct.press_abs = buf.get_f32_le();
26145 __struct.press_diff = buf.get_f32_le();
26146 __struct.temperature = buf.get_i16_le();
26147 __struct.temperature_press_diff = buf.get_i16_le();
26148 Ok(__struct)
26149 }
26150 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26151 let mut __tmp = BytesMut::new(bytes);
26152 #[allow(clippy::absurd_extreme_comparisons)]
26153 #[allow(unused_comparisons)]
26154 if __tmp.remaining() < Self::ENCODED_LEN {
26155 panic!(
26156 "buffer is too small (need {} bytes, but got {})",
26157 Self::ENCODED_LEN,
26158 __tmp.remaining(),
26159 )
26160 }
26161 __tmp.put_u32_le(self.time_boot_ms);
26162 __tmp.put_f32_le(self.press_abs);
26163 __tmp.put_f32_le(self.press_diff);
26164 __tmp.put_i16_le(self.temperature);
26165 __tmp.put_i16_le(self.temperature_press_diff);
26166 if matches!(version, MavlinkVersion::V2) {
26167 let len = __tmp.len();
26168 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26169 } else {
26170 __tmp.len()
26171 }
26172 }
26173}
26174#[doc = "id: 146"]
26175#[doc = "The smoothed, monotonic system state used to feed the control loops of the system."]
26176#[derive(Debug, Clone, PartialEq)]
26177#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26178#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26179pub struct CONTROL_SYSTEM_STATE_DATA {
26180 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26181 pub time_usec: u64,
26182 #[doc = "X acceleration in body frame"]
26183 pub x_acc: f32,
26184 #[doc = "Y acceleration in body frame"]
26185 pub y_acc: f32,
26186 #[doc = "Z acceleration in body frame"]
26187 pub z_acc: f32,
26188 #[doc = "X velocity in body frame"]
26189 pub x_vel: f32,
26190 #[doc = "Y velocity in body frame"]
26191 pub y_vel: f32,
26192 #[doc = "Z velocity in body frame"]
26193 pub z_vel: f32,
26194 #[doc = "X position in local frame"]
26195 pub x_pos: f32,
26196 #[doc = "Y position in local frame"]
26197 pub y_pos: f32,
26198 #[doc = "Z position in local frame"]
26199 pub z_pos: f32,
26200 #[doc = "Airspeed, set to -1 if unknown"]
26201 pub airspeed: f32,
26202 #[doc = "Variance of body velocity estimate"]
26203 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26204 pub vel_variance: [f32; 3],
26205 #[doc = "Variance in local position"]
26206 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26207 pub pos_variance: [f32; 3],
26208 #[doc = "The attitude, represented as Quaternion"]
26209 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26210 pub q: [f32; 4],
26211 #[doc = "Angular rate in roll axis"]
26212 pub roll_rate: f32,
26213 #[doc = "Angular rate in pitch axis"]
26214 pub pitch_rate: f32,
26215 #[doc = "Angular rate in yaw axis"]
26216 pub yaw_rate: f32,
26217}
26218impl CONTROL_SYSTEM_STATE_DATA {
26219 pub const ENCODED_LEN: usize = 100usize;
26220 pub const DEFAULT: Self = Self {
26221 time_usec: 0_u64,
26222 x_acc: 0.0_f32,
26223 y_acc: 0.0_f32,
26224 z_acc: 0.0_f32,
26225 x_vel: 0.0_f32,
26226 y_vel: 0.0_f32,
26227 z_vel: 0.0_f32,
26228 x_pos: 0.0_f32,
26229 y_pos: 0.0_f32,
26230 z_pos: 0.0_f32,
26231 airspeed: 0.0_f32,
26232 vel_variance: [0.0_f32; 3usize],
26233 pos_variance: [0.0_f32; 3usize],
26234 q: [0.0_f32; 4usize],
26235 roll_rate: 0.0_f32,
26236 pitch_rate: 0.0_f32,
26237 yaw_rate: 0.0_f32,
26238 };
26239 #[cfg(feature = "arbitrary")]
26240 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26241 use arbitrary::{Arbitrary, Unstructured};
26242 let mut buf = [0u8; 1024];
26243 rng.fill_bytes(&mut buf);
26244 let mut unstructured = Unstructured::new(&buf);
26245 Self::arbitrary(&mut unstructured).unwrap_or_default()
26246 }
26247}
26248impl Default for CONTROL_SYSTEM_STATE_DATA {
26249 fn default() -> Self {
26250 Self::DEFAULT.clone()
26251 }
26252}
26253impl MessageData for CONTROL_SYSTEM_STATE_DATA {
26254 type Message = MavMessage;
26255 const ID: u32 = 146u32;
26256 const NAME: &'static str = "CONTROL_SYSTEM_STATE";
26257 const EXTRA_CRC: u8 = 103u8;
26258 const ENCODED_LEN: usize = 100usize;
26259 fn deser(
26260 _version: MavlinkVersion,
26261 __input: &[u8],
26262 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26263 let avail_len = __input.len();
26264 let mut payload_buf = [0; Self::ENCODED_LEN];
26265 let mut buf = if avail_len < Self::ENCODED_LEN {
26266 payload_buf[0..avail_len].copy_from_slice(__input);
26267 Bytes::new(&payload_buf)
26268 } else {
26269 Bytes::new(__input)
26270 };
26271 let mut __struct = Self::default();
26272 __struct.time_usec = buf.get_u64_le();
26273 __struct.x_acc = buf.get_f32_le();
26274 __struct.y_acc = buf.get_f32_le();
26275 __struct.z_acc = buf.get_f32_le();
26276 __struct.x_vel = buf.get_f32_le();
26277 __struct.y_vel = buf.get_f32_le();
26278 __struct.z_vel = buf.get_f32_le();
26279 __struct.x_pos = buf.get_f32_le();
26280 __struct.y_pos = buf.get_f32_le();
26281 __struct.z_pos = buf.get_f32_le();
26282 __struct.airspeed = buf.get_f32_le();
26283 for v in &mut __struct.vel_variance {
26284 let val = buf.get_f32_le();
26285 *v = val;
26286 }
26287 for v in &mut __struct.pos_variance {
26288 let val = buf.get_f32_le();
26289 *v = val;
26290 }
26291 for v in &mut __struct.q {
26292 let val = buf.get_f32_le();
26293 *v = val;
26294 }
26295 __struct.roll_rate = buf.get_f32_le();
26296 __struct.pitch_rate = buf.get_f32_le();
26297 __struct.yaw_rate = buf.get_f32_le();
26298 Ok(__struct)
26299 }
26300 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26301 let mut __tmp = BytesMut::new(bytes);
26302 #[allow(clippy::absurd_extreme_comparisons)]
26303 #[allow(unused_comparisons)]
26304 if __tmp.remaining() < Self::ENCODED_LEN {
26305 panic!(
26306 "buffer is too small (need {} bytes, but got {})",
26307 Self::ENCODED_LEN,
26308 __tmp.remaining(),
26309 )
26310 }
26311 __tmp.put_u64_le(self.time_usec);
26312 __tmp.put_f32_le(self.x_acc);
26313 __tmp.put_f32_le(self.y_acc);
26314 __tmp.put_f32_le(self.z_acc);
26315 __tmp.put_f32_le(self.x_vel);
26316 __tmp.put_f32_le(self.y_vel);
26317 __tmp.put_f32_le(self.z_vel);
26318 __tmp.put_f32_le(self.x_pos);
26319 __tmp.put_f32_le(self.y_pos);
26320 __tmp.put_f32_le(self.z_pos);
26321 __tmp.put_f32_le(self.airspeed);
26322 for val in &self.vel_variance {
26323 __tmp.put_f32_le(*val);
26324 }
26325 for val in &self.pos_variance {
26326 __tmp.put_f32_le(*val);
26327 }
26328 for val in &self.q {
26329 __tmp.put_f32_le(*val);
26330 }
26331 __tmp.put_f32_le(self.roll_rate);
26332 __tmp.put_f32_le(self.pitch_rate);
26333 __tmp.put_f32_le(self.yaw_rate);
26334 if matches!(version, MavlinkVersion::V2) {
26335 let len = __tmp.len();
26336 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26337 } else {
26338 __tmp.len()
26339 }
26340 }
26341}
26342#[doc = "id: 37"]
26343#[doc = "Request a partial list of mission items from the system/component. <https://mavlink.io/en/services/mission.html>. If start and end index are the same, just send one waypoint."]
26344#[derive(Debug, Clone, PartialEq)]
26345#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26346#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26347pub struct MISSION_REQUEST_PARTIAL_LIST_DATA {
26348 #[doc = "Start index"]
26349 pub start_index: i16,
26350 #[doc = "End index, -1 by default (-1: send list to end). Else a valid index of the list"]
26351 pub end_index: i16,
26352 #[doc = "System ID"]
26353 pub target_system: u8,
26354 #[doc = "Component ID"]
26355 pub target_component: u8,
26356 #[doc = "Mission type."]
26357 #[cfg_attr(feature = "serde", serde(default))]
26358 pub mission_type: MavMissionType,
26359}
26360impl MISSION_REQUEST_PARTIAL_LIST_DATA {
26361 pub const ENCODED_LEN: usize = 7usize;
26362 pub const DEFAULT: Self = Self {
26363 start_index: 0_i16,
26364 end_index: 0_i16,
26365 target_system: 0_u8,
26366 target_component: 0_u8,
26367 mission_type: MavMissionType::DEFAULT,
26368 };
26369 #[cfg(feature = "arbitrary")]
26370 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26371 use arbitrary::{Arbitrary, Unstructured};
26372 let mut buf = [0u8; 1024];
26373 rng.fill_bytes(&mut buf);
26374 let mut unstructured = Unstructured::new(&buf);
26375 Self::arbitrary(&mut unstructured).unwrap_or_default()
26376 }
26377}
26378impl Default for MISSION_REQUEST_PARTIAL_LIST_DATA {
26379 fn default() -> Self {
26380 Self::DEFAULT.clone()
26381 }
26382}
26383impl MessageData for MISSION_REQUEST_PARTIAL_LIST_DATA {
26384 type Message = MavMessage;
26385 const ID: u32 = 37u32;
26386 const NAME: &'static str = "MISSION_REQUEST_PARTIAL_LIST";
26387 const EXTRA_CRC: u8 = 212u8;
26388 const ENCODED_LEN: usize = 7usize;
26389 fn deser(
26390 _version: MavlinkVersion,
26391 __input: &[u8],
26392 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26393 let avail_len = __input.len();
26394 let mut payload_buf = [0; Self::ENCODED_LEN];
26395 let mut buf = if avail_len < Self::ENCODED_LEN {
26396 payload_buf[0..avail_len].copy_from_slice(__input);
26397 Bytes::new(&payload_buf)
26398 } else {
26399 Bytes::new(__input)
26400 };
26401 let mut __struct = Self::default();
26402 __struct.start_index = buf.get_i16_le();
26403 __struct.end_index = buf.get_i16_le();
26404 __struct.target_system = buf.get_u8();
26405 __struct.target_component = buf.get_u8();
26406 let tmp = buf.get_u8();
26407 __struct.mission_type =
26408 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26409 enum_type: "MavMissionType",
26410 value: tmp as u32,
26411 })?;
26412 Ok(__struct)
26413 }
26414 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26415 let mut __tmp = BytesMut::new(bytes);
26416 #[allow(clippy::absurd_extreme_comparisons)]
26417 #[allow(unused_comparisons)]
26418 if __tmp.remaining() < Self::ENCODED_LEN {
26419 panic!(
26420 "buffer is too small (need {} bytes, but got {})",
26421 Self::ENCODED_LEN,
26422 __tmp.remaining(),
26423 )
26424 }
26425 __tmp.put_i16_le(self.start_index);
26426 __tmp.put_i16_le(self.end_index);
26427 __tmp.put_u8(self.target_system);
26428 __tmp.put_u8(self.target_component);
26429 __tmp.put_u8(self.mission_type as u8);
26430 if matches!(version, MavlinkVersion::V2) {
26431 let len = __tmp.len();
26432 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26433 } else {
26434 __tmp.len()
26435 }
26436 }
26437}
26438#[doc = "id: 242"]
26439#[doc = "Contains the home position. \tThe home position is the default position that the system will return to and land on. \tThe position must be set automatically by the system during the takeoff, and may also be explicitly set using MAV_CMD_DO_SET_HOME. \tThe global and local positions encode the position in the respective coordinate frames, while the q parameter encodes the orientation of the surface. \tUnder normal conditions it describes the heading and terrain slope, which can be used by the aircraft to adjust the approach. \tThe approach 3D vector describes the point to which the system should fly in normal flight mode and then perform a landing sequence along the vector. Note: this message can be requested by sending the MAV_CMD_REQUEST_MESSAGE with param1=242 (or the deprecated MAV_CMD_GET_HOME_POSITION command)."]
26440#[derive(Debug, Clone, PartialEq)]
26441#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26442#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26443pub struct HOME_POSITION_DATA {
26444 #[doc = "Latitude (WGS84)"]
26445 pub latitude: i32,
26446 #[doc = "Longitude (WGS84)"]
26447 pub longitude: i32,
26448 #[doc = "Altitude (MSL). Positive for up."]
26449 pub altitude: i32,
26450 #[doc = "Local X position of this position in the local coordinate frame (NED)"]
26451 pub x: f32,
26452 #[doc = "Local Y position of this position in the local coordinate frame (NED)"]
26453 pub y: f32,
26454 #[doc = "Local Z position of this position in the local coordinate frame (NED: positive \"down\")"]
26455 pub z: f32,
26456 #[doc = "Quaternion indicating world-to-surface-normal and heading transformation of the takeoff position. Used to indicate the heading and slope of the ground. All fields should be set to NaN if an accurate quaternion for both heading and surface slope cannot be supplied."]
26457 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26458 pub q: [f32; 4],
26459 #[doc = "Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
26460 pub approach_x: f32,
26461 #[doc = "Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
26462 pub approach_y: f32,
26463 #[doc = "Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone."]
26464 pub approach_z: f32,
26465 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
26466 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26467 pub time_usec: u64,
26468}
26469impl HOME_POSITION_DATA {
26470 pub const ENCODED_LEN: usize = 60usize;
26471 pub const DEFAULT: Self = Self {
26472 latitude: 0_i32,
26473 longitude: 0_i32,
26474 altitude: 0_i32,
26475 x: 0.0_f32,
26476 y: 0.0_f32,
26477 z: 0.0_f32,
26478 q: [0.0_f32; 4usize],
26479 approach_x: 0.0_f32,
26480 approach_y: 0.0_f32,
26481 approach_z: 0.0_f32,
26482 time_usec: 0_u64,
26483 };
26484 #[cfg(feature = "arbitrary")]
26485 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26486 use arbitrary::{Arbitrary, Unstructured};
26487 let mut buf = [0u8; 1024];
26488 rng.fill_bytes(&mut buf);
26489 let mut unstructured = Unstructured::new(&buf);
26490 Self::arbitrary(&mut unstructured).unwrap_or_default()
26491 }
26492}
26493impl Default for HOME_POSITION_DATA {
26494 fn default() -> Self {
26495 Self::DEFAULT.clone()
26496 }
26497}
26498impl MessageData for HOME_POSITION_DATA {
26499 type Message = MavMessage;
26500 const ID: u32 = 242u32;
26501 const NAME: &'static str = "HOME_POSITION";
26502 const EXTRA_CRC: u8 = 104u8;
26503 const ENCODED_LEN: usize = 60usize;
26504 fn deser(
26505 _version: MavlinkVersion,
26506 __input: &[u8],
26507 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26508 let avail_len = __input.len();
26509 let mut payload_buf = [0; Self::ENCODED_LEN];
26510 let mut buf = if avail_len < Self::ENCODED_LEN {
26511 payload_buf[0..avail_len].copy_from_slice(__input);
26512 Bytes::new(&payload_buf)
26513 } else {
26514 Bytes::new(__input)
26515 };
26516 let mut __struct = Self::default();
26517 __struct.latitude = buf.get_i32_le();
26518 __struct.longitude = buf.get_i32_le();
26519 __struct.altitude = buf.get_i32_le();
26520 __struct.x = buf.get_f32_le();
26521 __struct.y = buf.get_f32_le();
26522 __struct.z = buf.get_f32_le();
26523 for v in &mut __struct.q {
26524 let val = buf.get_f32_le();
26525 *v = val;
26526 }
26527 __struct.approach_x = buf.get_f32_le();
26528 __struct.approach_y = buf.get_f32_le();
26529 __struct.approach_z = buf.get_f32_le();
26530 __struct.time_usec = buf.get_u64_le();
26531 Ok(__struct)
26532 }
26533 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26534 let mut __tmp = BytesMut::new(bytes);
26535 #[allow(clippy::absurd_extreme_comparisons)]
26536 #[allow(unused_comparisons)]
26537 if __tmp.remaining() < Self::ENCODED_LEN {
26538 panic!(
26539 "buffer is too small (need {} bytes, but got {})",
26540 Self::ENCODED_LEN,
26541 __tmp.remaining(),
26542 )
26543 }
26544 __tmp.put_i32_le(self.latitude);
26545 __tmp.put_i32_le(self.longitude);
26546 __tmp.put_i32_le(self.altitude);
26547 __tmp.put_f32_le(self.x);
26548 __tmp.put_f32_le(self.y);
26549 __tmp.put_f32_le(self.z);
26550 for val in &self.q {
26551 __tmp.put_f32_le(*val);
26552 }
26553 __tmp.put_f32_le(self.approach_x);
26554 __tmp.put_f32_le(self.approach_y);
26555 __tmp.put_f32_le(self.approach_z);
26556 __tmp.put_u64_le(self.time_usec);
26557 if matches!(version, MavlinkVersion::V2) {
26558 let len = __tmp.len();
26559 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26560 } else {
26561 __tmp.len()
26562 }
26563 }
26564}
26565#[doc = "id: 275"]
26566#[doc = "Camera tracking status, sent while in active tracking. Use MAV_CMD_SET_MESSAGE_INTERVAL to define message interval."]
26567#[derive(Debug, Clone, PartialEq)]
26568#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26569#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26570pub struct CAMERA_TRACKING_IMAGE_STATUS_DATA {
26571 #[doc = "Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
26572 pub point_x: f32,
26573 #[doc = "Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
26574 pub point_y: f32,
26575 #[doc = "Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown"]
26576 pub radius: f32,
26577 #[doc = "Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
26578 pub rec_top_x: f32,
26579 #[doc = "Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
26580 pub rec_top_y: f32,
26581 #[doc = "Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown"]
26582 pub rec_bottom_x: f32,
26583 #[doc = "Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown"]
26584 pub rec_bottom_y: f32,
26585 #[doc = "Current tracking status"]
26586 pub tracking_status: CameraTrackingStatusFlags,
26587 #[doc = "Current tracking mode"]
26588 pub tracking_mode: CameraTrackingMode,
26589 #[doc = "Defines location of target data"]
26590 pub target_data: CameraTrackingTargetData,
26591 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
26592 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
26593 pub camera_device_id: u8,
26594}
26595impl CAMERA_TRACKING_IMAGE_STATUS_DATA {
26596 pub const ENCODED_LEN: usize = 32usize;
26597 pub const DEFAULT: Self = Self {
26598 point_x: 0.0_f32,
26599 point_y: 0.0_f32,
26600 radius: 0.0_f32,
26601 rec_top_x: 0.0_f32,
26602 rec_top_y: 0.0_f32,
26603 rec_bottom_x: 0.0_f32,
26604 rec_bottom_y: 0.0_f32,
26605 tracking_status: CameraTrackingStatusFlags::DEFAULT,
26606 tracking_mode: CameraTrackingMode::DEFAULT,
26607 target_data: CameraTrackingTargetData::DEFAULT,
26608 camera_device_id: 0_u8,
26609 };
26610 #[cfg(feature = "arbitrary")]
26611 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26612 use arbitrary::{Arbitrary, Unstructured};
26613 let mut buf = [0u8; 1024];
26614 rng.fill_bytes(&mut buf);
26615 let mut unstructured = Unstructured::new(&buf);
26616 Self::arbitrary(&mut unstructured).unwrap_or_default()
26617 }
26618}
26619impl Default for CAMERA_TRACKING_IMAGE_STATUS_DATA {
26620 fn default() -> Self {
26621 Self::DEFAULT.clone()
26622 }
26623}
26624impl MessageData for CAMERA_TRACKING_IMAGE_STATUS_DATA {
26625 type Message = MavMessage;
26626 const ID: u32 = 275u32;
26627 const NAME: &'static str = "CAMERA_TRACKING_IMAGE_STATUS";
26628 const EXTRA_CRC: u8 = 126u8;
26629 const ENCODED_LEN: usize = 32usize;
26630 fn deser(
26631 _version: MavlinkVersion,
26632 __input: &[u8],
26633 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26634 let avail_len = __input.len();
26635 let mut payload_buf = [0; Self::ENCODED_LEN];
26636 let mut buf = if avail_len < Self::ENCODED_LEN {
26637 payload_buf[0..avail_len].copy_from_slice(__input);
26638 Bytes::new(&payload_buf)
26639 } else {
26640 Bytes::new(__input)
26641 };
26642 let mut __struct = Self::default();
26643 __struct.point_x = buf.get_f32_le();
26644 __struct.point_y = buf.get_f32_le();
26645 __struct.radius = buf.get_f32_le();
26646 __struct.rec_top_x = buf.get_f32_le();
26647 __struct.rec_top_y = buf.get_f32_le();
26648 __struct.rec_bottom_x = buf.get_f32_le();
26649 __struct.rec_bottom_y = buf.get_f32_le();
26650 let tmp = buf.get_u8();
26651 __struct.tracking_status =
26652 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26653 enum_type: "CameraTrackingStatusFlags",
26654 value: tmp as u32,
26655 })?;
26656 let tmp = buf.get_u8();
26657 __struct.tracking_mode =
26658 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
26659 enum_type: "CameraTrackingMode",
26660 value: tmp as u32,
26661 })?;
26662 let tmp = buf.get_u8();
26663 __struct.target_data =
26664 CameraTrackingTargetData::from_bits(tmp & CameraTrackingTargetData::all().bits())
26665 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
26666 flag_type: "CameraTrackingTargetData",
26667 value: tmp as u32,
26668 })?;
26669 __struct.camera_device_id = buf.get_u8();
26670 Ok(__struct)
26671 }
26672 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26673 let mut __tmp = BytesMut::new(bytes);
26674 #[allow(clippy::absurd_extreme_comparisons)]
26675 #[allow(unused_comparisons)]
26676 if __tmp.remaining() < Self::ENCODED_LEN {
26677 panic!(
26678 "buffer is too small (need {} bytes, but got {})",
26679 Self::ENCODED_LEN,
26680 __tmp.remaining(),
26681 )
26682 }
26683 __tmp.put_f32_le(self.point_x);
26684 __tmp.put_f32_le(self.point_y);
26685 __tmp.put_f32_le(self.radius);
26686 __tmp.put_f32_le(self.rec_top_x);
26687 __tmp.put_f32_le(self.rec_top_y);
26688 __tmp.put_f32_le(self.rec_bottom_x);
26689 __tmp.put_f32_le(self.rec_bottom_y);
26690 __tmp.put_u8(self.tracking_status as u8);
26691 __tmp.put_u8(self.tracking_mode as u8);
26692 __tmp.put_u8(self.target_data.bits());
26693 __tmp.put_u8(self.camera_device_id);
26694 if matches!(version, MavlinkVersion::V2) {
26695 let len = __tmp.len();
26696 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26697 } else {
26698 __tmp.len()
26699 }
26700 }
26701}
26702#[doc = "id: 375"]
26703#[doc = "The raw values of the actuator outputs (e.g. on Pixhawk, from MAIN, AUX ports). This message supersedes SERVO_OUTPUT_RAW."]
26704#[derive(Debug, Clone, PartialEq)]
26705#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26706#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26707pub struct ACTUATOR_OUTPUT_STATUS_DATA {
26708 #[doc = "Timestamp (since system boot)."]
26709 pub time_usec: u64,
26710 #[doc = "Active outputs"]
26711 pub active: u32,
26712 #[doc = "Servo / motor output array values. Zero values indicate unused channels."]
26713 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
26714 pub actuator: [f32; 32],
26715}
26716impl ACTUATOR_OUTPUT_STATUS_DATA {
26717 pub const ENCODED_LEN: usize = 140usize;
26718 pub const DEFAULT: Self = Self {
26719 time_usec: 0_u64,
26720 active: 0_u32,
26721 actuator: [0.0_f32; 32usize],
26722 };
26723 #[cfg(feature = "arbitrary")]
26724 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26725 use arbitrary::{Arbitrary, Unstructured};
26726 let mut buf = [0u8; 1024];
26727 rng.fill_bytes(&mut buf);
26728 let mut unstructured = Unstructured::new(&buf);
26729 Self::arbitrary(&mut unstructured).unwrap_or_default()
26730 }
26731}
26732impl Default for ACTUATOR_OUTPUT_STATUS_DATA {
26733 fn default() -> Self {
26734 Self::DEFAULT.clone()
26735 }
26736}
26737impl MessageData for ACTUATOR_OUTPUT_STATUS_DATA {
26738 type Message = MavMessage;
26739 const ID: u32 = 375u32;
26740 const NAME: &'static str = "ACTUATOR_OUTPUT_STATUS";
26741 const EXTRA_CRC: u8 = 251u8;
26742 const ENCODED_LEN: usize = 140usize;
26743 fn deser(
26744 _version: MavlinkVersion,
26745 __input: &[u8],
26746 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26747 let avail_len = __input.len();
26748 let mut payload_buf = [0; Self::ENCODED_LEN];
26749 let mut buf = if avail_len < Self::ENCODED_LEN {
26750 payload_buf[0..avail_len].copy_from_slice(__input);
26751 Bytes::new(&payload_buf)
26752 } else {
26753 Bytes::new(__input)
26754 };
26755 let mut __struct = Self::default();
26756 __struct.time_usec = buf.get_u64_le();
26757 __struct.active = buf.get_u32_le();
26758 for v in &mut __struct.actuator {
26759 let val = buf.get_f32_le();
26760 *v = val;
26761 }
26762 Ok(__struct)
26763 }
26764 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26765 let mut __tmp = BytesMut::new(bytes);
26766 #[allow(clippy::absurd_extreme_comparisons)]
26767 #[allow(unused_comparisons)]
26768 if __tmp.remaining() < Self::ENCODED_LEN {
26769 panic!(
26770 "buffer is too small (need {} bytes, but got {})",
26771 Self::ENCODED_LEN,
26772 __tmp.remaining(),
26773 )
26774 }
26775 __tmp.put_u64_le(self.time_usec);
26776 __tmp.put_u32_le(self.active);
26777 for val in &self.actuator {
26778 __tmp.put_f32_le(*val);
26779 }
26780 if matches!(version, MavlinkVersion::V2) {
26781 let len = __tmp.len();
26782 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26783 } else {
26784 __tmp.len()
26785 }
26786 }
26787}
26788#[doc = "id: 122"]
26789#[doc = "Stop log transfer and resume normal logging."]
26790#[derive(Debug, Clone, PartialEq)]
26791#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26792#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26793pub struct LOG_REQUEST_END_DATA {
26794 #[doc = "System ID"]
26795 pub target_system: u8,
26796 #[doc = "Component ID"]
26797 pub target_component: u8,
26798}
26799impl LOG_REQUEST_END_DATA {
26800 pub const ENCODED_LEN: usize = 2usize;
26801 pub const DEFAULT: Self = Self {
26802 target_system: 0_u8,
26803 target_component: 0_u8,
26804 };
26805 #[cfg(feature = "arbitrary")]
26806 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26807 use arbitrary::{Arbitrary, Unstructured};
26808 let mut buf = [0u8; 1024];
26809 rng.fill_bytes(&mut buf);
26810 let mut unstructured = Unstructured::new(&buf);
26811 Self::arbitrary(&mut unstructured).unwrap_or_default()
26812 }
26813}
26814impl Default for LOG_REQUEST_END_DATA {
26815 fn default() -> Self {
26816 Self::DEFAULT.clone()
26817 }
26818}
26819impl MessageData for LOG_REQUEST_END_DATA {
26820 type Message = MavMessage;
26821 const ID: u32 = 122u32;
26822 const NAME: &'static str = "LOG_REQUEST_END";
26823 const EXTRA_CRC: u8 = 203u8;
26824 const ENCODED_LEN: usize = 2usize;
26825 fn deser(
26826 _version: MavlinkVersion,
26827 __input: &[u8],
26828 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26829 let avail_len = __input.len();
26830 let mut payload_buf = [0; Self::ENCODED_LEN];
26831 let mut buf = if avail_len < Self::ENCODED_LEN {
26832 payload_buf[0..avail_len].copy_from_slice(__input);
26833 Bytes::new(&payload_buf)
26834 } else {
26835 Bytes::new(__input)
26836 };
26837 let mut __struct = Self::default();
26838 __struct.target_system = buf.get_u8();
26839 __struct.target_component = buf.get_u8();
26840 Ok(__struct)
26841 }
26842 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26843 let mut __tmp = BytesMut::new(bytes);
26844 #[allow(clippy::absurd_extreme_comparisons)]
26845 #[allow(unused_comparisons)]
26846 if __tmp.remaining() < Self::ENCODED_LEN {
26847 panic!(
26848 "buffer is too small (need {} bytes, but got {})",
26849 Self::ENCODED_LEN,
26850 __tmp.remaining(),
26851 )
26852 }
26853 __tmp.put_u8(self.target_system);
26854 __tmp.put_u8(self.target_component);
26855 if matches!(version, MavlinkVersion::V2) {
26856 let len = __tmp.len();
26857 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
26858 } else {
26859 __tmp.len()
26860 }
26861 }
26862}
26863#[doc = "id: 65"]
26864#[doc = "The PPM values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. A value of UINT16_MAX implies the channel is unused. Individual receivers/transmitters might violate this specification."]
26865#[derive(Debug, Clone, PartialEq)]
26866#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
26867#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
26868pub struct RC_CHANNELS_DATA {
26869 #[doc = "Timestamp (time since system boot)."]
26870 pub time_boot_ms: u32,
26871 #[doc = "RC channel 1 value."]
26872 pub chan1_raw: u16,
26873 #[doc = "RC channel 2 value."]
26874 pub chan2_raw: u16,
26875 #[doc = "RC channel 3 value."]
26876 pub chan3_raw: u16,
26877 #[doc = "RC channel 4 value."]
26878 pub chan4_raw: u16,
26879 #[doc = "RC channel 5 value."]
26880 pub chan5_raw: u16,
26881 #[doc = "RC channel 6 value."]
26882 pub chan6_raw: u16,
26883 #[doc = "RC channel 7 value."]
26884 pub chan7_raw: u16,
26885 #[doc = "RC channel 8 value."]
26886 pub chan8_raw: u16,
26887 #[doc = "RC channel 9 value."]
26888 pub chan9_raw: u16,
26889 #[doc = "RC channel 10 value."]
26890 pub chan10_raw: u16,
26891 #[doc = "RC channel 11 value."]
26892 pub chan11_raw: u16,
26893 #[doc = "RC channel 12 value."]
26894 pub chan12_raw: u16,
26895 #[doc = "RC channel 13 value."]
26896 pub chan13_raw: u16,
26897 #[doc = "RC channel 14 value."]
26898 pub chan14_raw: u16,
26899 #[doc = "RC channel 15 value."]
26900 pub chan15_raw: u16,
26901 #[doc = "RC channel 16 value."]
26902 pub chan16_raw: u16,
26903 #[doc = "RC channel 17 value."]
26904 pub chan17_raw: u16,
26905 #[doc = "RC channel 18 value."]
26906 pub chan18_raw: u16,
26907 #[doc = "Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available."]
26908 pub chancount: u8,
26909 #[doc = "Receive signal strength indicator in device-dependent units/scale. Values: [0-254], UINT8_MAX: invalid/unknown."]
26910 pub rssi: u8,
26911}
26912impl RC_CHANNELS_DATA {
26913 pub const ENCODED_LEN: usize = 42usize;
26914 pub const DEFAULT: Self = Self {
26915 time_boot_ms: 0_u32,
26916 chan1_raw: 0_u16,
26917 chan2_raw: 0_u16,
26918 chan3_raw: 0_u16,
26919 chan4_raw: 0_u16,
26920 chan5_raw: 0_u16,
26921 chan6_raw: 0_u16,
26922 chan7_raw: 0_u16,
26923 chan8_raw: 0_u16,
26924 chan9_raw: 0_u16,
26925 chan10_raw: 0_u16,
26926 chan11_raw: 0_u16,
26927 chan12_raw: 0_u16,
26928 chan13_raw: 0_u16,
26929 chan14_raw: 0_u16,
26930 chan15_raw: 0_u16,
26931 chan16_raw: 0_u16,
26932 chan17_raw: 0_u16,
26933 chan18_raw: 0_u16,
26934 chancount: 0_u8,
26935 rssi: 0_u8,
26936 };
26937 #[cfg(feature = "arbitrary")]
26938 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
26939 use arbitrary::{Arbitrary, Unstructured};
26940 let mut buf = [0u8; 1024];
26941 rng.fill_bytes(&mut buf);
26942 let mut unstructured = Unstructured::new(&buf);
26943 Self::arbitrary(&mut unstructured).unwrap_or_default()
26944 }
26945}
26946impl Default for RC_CHANNELS_DATA {
26947 fn default() -> Self {
26948 Self::DEFAULT.clone()
26949 }
26950}
26951impl MessageData for RC_CHANNELS_DATA {
26952 type Message = MavMessage;
26953 const ID: u32 = 65u32;
26954 const NAME: &'static str = "RC_CHANNELS";
26955 const EXTRA_CRC: u8 = 118u8;
26956 const ENCODED_LEN: usize = 42usize;
26957 fn deser(
26958 _version: MavlinkVersion,
26959 __input: &[u8],
26960 ) -> Result<Self, ::mavlink_core::error::ParserError> {
26961 let avail_len = __input.len();
26962 let mut payload_buf = [0; Self::ENCODED_LEN];
26963 let mut buf = if avail_len < Self::ENCODED_LEN {
26964 payload_buf[0..avail_len].copy_from_slice(__input);
26965 Bytes::new(&payload_buf)
26966 } else {
26967 Bytes::new(__input)
26968 };
26969 let mut __struct = Self::default();
26970 __struct.time_boot_ms = buf.get_u32_le();
26971 __struct.chan1_raw = buf.get_u16_le();
26972 __struct.chan2_raw = buf.get_u16_le();
26973 __struct.chan3_raw = buf.get_u16_le();
26974 __struct.chan4_raw = buf.get_u16_le();
26975 __struct.chan5_raw = buf.get_u16_le();
26976 __struct.chan6_raw = buf.get_u16_le();
26977 __struct.chan7_raw = buf.get_u16_le();
26978 __struct.chan8_raw = buf.get_u16_le();
26979 __struct.chan9_raw = buf.get_u16_le();
26980 __struct.chan10_raw = buf.get_u16_le();
26981 __struct.chan11_raw = buf.get_u16_le();
26982 __struct.chan12_raw = buf.get_u16_le();
26983 __struct.chan13_raw = buf.get_u16_le();
26984 __struct.chan14_raw = buf.get_u16_le();
26985 __struct.chan15_raw = buf.get_u16_le();
26986 __struct.chan16_raw = buf.get_u16_le();
26987 __struct.chan17_raw = buf.get_u16_le();
26988 __struct.chan18_raw = buf.get_u16_le();
26989 __struct.chancount = buf.get_u8();
26990 __struct.rssi = buf.get_u8();
26991 Ok(__struct)
26992 }
26993 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
26994 let mut __tmp = BytesMut::new(bytes);
26995 #[allow(clippy::absurd_extreme_comparisons)]
26996 #[allow(unused_comparisons)]
26997 if __tmp.remaining() < Self::ENCODED_LEN {
26998 panic!(
26999 "buffer is too small (need {} bytes, but got {})",
27000 Self::ENCODED_LEN,
27001 __tmp.remaining(),
27002 )
27003 }
27004 __tmp.put_u32_le(self.time_boot_ms);
27005 __tmp.put_u16_le(self.chan1_raw);
27006 __tmp.put_u16_le(self.chan2_raw);
27007 __tmp.put_u16_le(self.chan3_raw);
27008 __tmp.put_u16_le(self.chan4_raw);
27009 __tmp.put_u16_le(self.chan5_raw);
27010 __tmp.put_u16_le(self.chan6_raw);
27011 __tmp.put_u16_le(self.chan7_raw);
27012 __tmp.put_u16_le(self.chan8_raw);
27013 __tmp.put_u16_le(self.chan9_raw);
27014 __tmp.put_u16_le(self.chan10_raw);
27015 __tmp.put_u16_le(self.chan11_raw);
27016 __tmp.put_u16_le(self.chan12_raw);
27017 __tmp.put_u16_le(self.chan13_raw);
27018 __tmp.put_u16_le(self.chan14_raw);
27019 __tmp.put_u16_le(self.chan15_raw);
27020 __tmp.put_u16_le(self.chan16_raw);
27021 __tmp.put_u16_le(self.chan17_raw);
27022 __tmp.put_u16_le(self.chan18_raw);
27023 __tmp.put_u8(self.chancount);
27024 __tmp.put_u8(self.rssi);
27025 if matches!(version, MavlinkVersion::V2) {
27026 let len = __tmp.len();
27027 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27028 } else {
27029 __tmp.len()
27030 }
27031 }
27032}
27033#[doc = "id: 61"]
27034#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
27035#[derive(Debug, Clone, PartialEq)]
27036#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27037#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27038pub struct ATTITUDE_QUATERNION_COV_DATA {
27039 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27040 pub time_usec: u64,
27041 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)"]
27042 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27043 pub q: [f32; 4],
27044 #[doc = "Roll angular speed"]
27045 pub rollspeed: f32,
27046 #[doc = "Pitch angular speed"]
27047 pub pitchspeed: f32,
27048 #[doc = "Yaw angular speed"]
27049 pub yawspeed: f32,
27050 #[doc = "Row-major representation of a 3x3 attitude covariance matrix (states: roll, pitch, yaw; first three entries are the first ROW, next three entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
27051 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27052 pub covariance: [f32; 9],
27053}
27054impl ATTITUDE_QUATERNION_COV_DATA {
27055 pub const ENCODED_LEN: usize = 72usize;
27056 pub const DEFAULT: Self = Self {
27057 time_usec: 0_u64,
27058 q: [0.0_f32; 4usize],
27059 rollspeed: 0.0_f32,
27060 pitchspeed: 0.0_f32,
27061 yawspeed: 0.0_f32,
27062 covariance: [0.0_f32; 9usize],
27063 };
27064 #[cfg(feature = "arbitrary")]
27065 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27066 use arbitrary::{Arbitrary, Unstructured};
27067 let mut buf = [0u8; 1024];
27068 rng.fill_bytes(&mut buf);
27069 let mut unstructured = Unstructured::new(&buf);
27070 Self::arbitrary(&mut unstructured).unwrap_or_default()
27071 }
27072}
27073impl Default for ATTITUDE_QUATERNION_COV_DATA {
27074 fn default() -> Self {
27075 Self::DEFAULT.clone()
27076 }
27077}
27078impl MessageData for ATTITUDE_QUATERNION_COV_DATA {
27079 type Message = MavMessage;
27080 const ID: u32 = 61u32;
27081 const NAME: &'static str = "ATTITUDE_QUATERNION_COV";
27082 const EXTRA_CRC: u8 = 167u8;
27083 const ENCODED_LEN: usize = 72usize;
27084 fn deser(
27085 _version: MavlinkVersion,
27086 __input: &[u8],
27087 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27088 let avail_len = __input.len();
27089 let mut payload_buf = [0; Self::ENCODED_LEN];
27090 let mut buf = if avail_len < Self::ENCODED_LEN {
27091 payload_buf[0..avail_len].copy_from_slice(__input);
27092 Bytes::new(&payload_buf)
27093 } else {
27094 Bytes::new(__input)
27095 };
27096 let mut __struct = Self::default();
27097 __struct.time_usec = buf.get_u64_le();
27098 for v in &mut __struct.q {
27099 let val = buf.get_f32_le();
27100 *v = val;
27101 }
27102 __struct.rollspeed = buf.get_f32_le();
27103 __struct.pitchspeed = buf.get_f32_le();
27104 __struct.yawspeed = buf.get_f32_le();
27105 for v in &mut __struct.covariance {
27106 let val = buf.get_f32_le();
27107 *v = val;
27108 }
27109 Ok(__struct)
27110 }
27111 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27112 let mut __tmp = BytesMut::new(bytes);
27113 #[allow(clippy::absurd_extreme_comparisons)]
27114 #[allow(unused_comparisons)]
27115 if __tmp.remaining() < Self::ENCODED_LEN {
27116 panic!(
27117 "buffer is too small (need {} bytes, but got {})",
27118 Self::ENCODED_LEN,
27119 __tmp.remaining(),
27120 )
27121 }
27122 __tmp.put_u64_le(self.time_usec);
27123 for val in &self.q {
27124 __tmp.put_f32_le(*val);
27125 }
27126 __tmp.put_f32_le(self.rollspeed);
27127 __tmp.put_f32_le(self.pitchspeed);
27128 __tmp.put_f32_le(self.yawspeed);
27129 for val in &self.covariance {
27130 __tmp.put_f32_le(*val);
27131 }
27132 if matches!(version, MavlinkVersion::V2) {
27133 let len = __tmp.len();
27134 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27135 } else {
27136 __tmp.len()
27137 }
27138 }
27139}
27140#[doc = "id: 112"]
27141#[doc = "Camera-IMU triggering and synchronisation message."]
27142#[derive(Debug, Clone, PartialEq)]
27143#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27144#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27145pub struct CAMERA_TRIGGER_DATA {
27146 #[doc = "Timestamp for image frame (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27147 pub time_usec: u64,
27148 #[doc = "Image frame sequence"]
27149 pub seq: u32,
27150}
27151impl CAMERA_TRIGGER_DATA {
27152 pub const ENCODED_LEN: usize = 12usize;
27153 pub const DEFAULT: Self = Self {
27154 time_usec: 0_u64,
27155 seq: 0_u32,
27156 };
27157 #[cfg(feature = "arbitrary")]
27158 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27159 use arbitrary::{Arbitrary, Unstructured};
27160 let mut buf = [0u8; 1024];
27161 rng.fill_bytes(&mut buf);
27162 let mut unstructured = Unstructured::new(&buf);
27163 Self::arbitrary(&mut unstructured).unwrap_or_default()
27164 }
27165}
27166impl Default for CAMERA_TRIGGER_DATA {
27167 fn default() -> Self {
27168 Self::DEFAULT.clone()
27169 }
27170}
27171impl MessageData for CAMERA_TRIGGER_DATA {
27172 type Message = MavMessage;
27173 const ID: u32 = 112u32;
27174 const NAME: &'static str = "CAMERA_TRIGGER";
27175 const EXTRA_CRC: u8 = 174u8;
27176 const ENCODED_LEN: usize = 12usize;
27177 fn deser(
27178 _version: MavlinkVersion,
27179 __input: &[u8],
27180 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27181 let avail_len = __input.len();
27182 let mut payload_buf = [0; Self::ENCODED_LEN];
27183 let mut buf = if avail_len < Self::ENCODED_LEN {
27184 payload_buf[0..avail_len].copy_from_slice(__input);
27185 Bytes::new(&payload_buf)
27186 } else {
27187 Bytes::new(__input)
27188 };
27189 let mut __struct = Self::default();
27190 __struct.time_usec = buf.get_u64_le();
27191 __struct.seq = buf.get_u32_le();
27192 Ok(__struct)
27193 }
27194 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27195 let mut __tmp = BytesMut::new(bytes);
27196 #[allow(clippy::absurd_extreme_comparisons)]
27197 #[allow(unused_comparisons)]
27198 if __tmp.remaining() < Self::ENCODED_LEN {
27199 panic!(
27200 "buffer is too small (need {} bytes, but got {})",
27201 Self::ENCODED_LEN,
27202 __tmp.remaining(),
27203 )
27204 }
27205 __tmp.put_u64_le(self.time_usec);
27206 __tmp.put_u32_le(self.seq);
27207 if matches!(version, MavlinkVersion::V2) {
27208 let len = __tmp.len();
27209 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27210 } else {
27211 __tmp.len()
27212 }
27213 }
27214}
27215#[doc = "id: 144"]
27216#[doc = "Current motion information from a designated system."]
27217#[derive(Debug, Clone, PartialEq)]
27218#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27219#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27220pub struct FOLLOW_TARGET_DATA {
27221 #[doc = "Timestamp (time since system boot)."]
27222 pub timestamp: u64,
27223 #[doc = "button states or switches of a tracker device"]
27224 pub custom_state: u64,
27225 #[doc = "Latitude (WGS84)"]
27226 pub lat: i32,
27227 #[doc = "Longitude (WGS84)"]
27228 pub lon: i32,
27229 #[doc = "Altitude (MSL)"]
27230 pub alt: f32,
27231 #[doc = "target velocity (0,0,0) for unknown"]
27232 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27233 pub vel: [f32; 3],
27234 #[doc = "linear target acceleration (0,0,0) for unknown"]
27235 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27236 pub acc: [f32; 3],
27237 #[doc = "(0 0 0 0 for unknown)"]
27238 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27239 pub attitude_q: [f32; 4],
27240 #[doc = "(0 0 0 for unknown)"]
27241 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27242 pub rates: [f32; 3],
27243 #[doc = "eph epv"]
27244 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27245 pub position_cov: [f32; 3],
27246 #[doc = "bit positions for tracker reporting capabilities (POS = 0, VEL = 1, ACCEL = 2, ATT + RATES = 3)"]
27247 pub est_capabilities: u8,
27248}
27249impl FOLLOW_TARGET_DATA {
27250 pub const ENCODED_LEN: usize = 93usize;
27251 pub const DEFAULT: Self = Self {
27252 timestamp: 0_u64,
27253 custom_state: 0_u64,
27254 lat: 0_i32,
27255 lon: 0_i32,
27256 alt: 0.0_f32,
27257 vel: [0.0_f32; 3usize],
27258 acc: [0.0_f32; 3usize],
27259 attitude_q: [0.0_f32; 4usize],
27260 rates: [0.0_f32; 3usize],
27261 position_cov: [0.0_f32; 3usize],
27262 est_capabilities: 0_u8,
27263 };
27264 #[cfg(feature = "arbitrary")]
27265 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27266 use arbitrary::{Arbitrary, Unstructured};
27267 let mut buf = [0u8; 1024];
27268 rng.fill_bytes(&mut buf);
27269 let mut unstructured = Unstructured::new(&buf);
27270 Self::arbitrary(&mut unstructured).unwrap_or_default()
27271 }
27272}
27273impl Default for FOLLOW_TARGET_DATA {
27274 fn default() -> Self {
27275 Self::DEFAULT.clone()
27276 }
27277}
27278impl MessageData for FOLLOW_TARGET_DATA {
27279 type Message = MavMessage;
27280 const ID: u32 = 144u32;
27281 const NAME: &'static str = "FOLLOW_TARGET";
27282 const EXTRA_CRC: u8 = 127u8;
27283 const ENCODED_LEN: usize = 93usize;
27284 fn deser(
27285 _version: MavlinkVersion,
27286 __input: &[u8],
27287 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27288 let avail_len = __input.len();
27289 let mut payload_buf = [0; Self::ENCODED_LEN];
27290 let mut buf = if avail_len < Self::ENCODED_LEN {
27291 payload_buf[0..avail_len].copy_from_slice(__input);
27292 Bytes::new(&payload_buf)
27293 } else {
27294 Bytes::new(__input)
27295 };
27296 let mut __struct = Self::default();
27297 __struct.timestamp = buf.get_u64_le();
27298 __struct.custom_state = buf.get_u64_le();
27299 __struct.lat = buf.get_i32_le();
27300 __struct.lon = buf.get_i32_le();
27301 __struct.alt = buf.get_f32_le();
27302 for v in &mut __struct.vel {
27303 let val = buf.get_f32_le();
27304 *v = val;
27305 }
27306 for v in &mut __struct.acc {
27307 let val = buf.get_f32_le();
27308 *v = val;
27309 }
27310 for v in &mut __struct.attitude_q {
27311 let val = buf.get_f32_le();
27312 *v = val;
27313 }
27314 for v in &mut __struct.rates {
27315 let val = buf.get_f32_le();
27316 *v = val;
27317 }
27318 for v in &mut __struct.position_cov {
27319 let val = buf.get_f32_le();
27320 *v = val;
27321 }
27322 __struct.est_capabilities = buf.get_u8();
27323 Ok(__struct)
27324 }
27325 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27326 let mut __tmp = BytesMut::new(bytes);
27327 #[allow(clippy::absurd_extreme_comparisons)]
27328 #[allow(unused_comparisons)]
27329 if __tmp.remaining() < Self::ENCODED_LEN {
27330 panic!(
27331 "buffer is too small (need {} bytes, but got {})",
27332 Self::ENCODED_LEN,
27333 __tmp.remaining(),
27334 )
27335 }
27336 __tmp.put_u64_le(self.timestamp);
27337 __tmp.put_u64_le(self.custom_state);
27338 __tmp.put_i32_le(self.lat);
27339 __tmp.put_i32_le(self.lon);
27340 __tmp.put_f32_le(self.alt);
27341 for val in &self.vel {
27342 __tmp.put_f32_le(*val);
27343 }
27344 for val in &self.acc {
27345 __tmp.put_f32_le(*val);
27346 }
27347 for val in &self.attitude_q {
27348 __tmp.put_f32_le(*val);
27349 }
27350 for val in &self.rates {
27351 __tmp.put_f32_le(*val);
27352 }
27353 for val in &self.position_cov {
27354 __tmp.put_f32_le(*val);
27355 }
27356 __tmp.put_u8(self.est_capabilities);
27357 if matches!(version, MavlinkVersion::V2) {
27358 let len = __tmp.len();
27359 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27360 } else {
27361 __tmp.len()
27362 }
27363 }
27364}
27365#[doc = "id: 63"]
27366#[doc = "The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It is designed as scaled integer message since the resolution of float is not sufficient. NOTE: This message is intended for onboard networks / companion computers and higher-bandwidth links and optimized for accuracy and completeness. Please use the GLOBAL_POSITION_INT message for a minimal subset."]
27367#[derive(Debug, Clone, PartialEq)]
27368#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27369#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27370pub struct GLOBAL_POSITION_INT_COV_DATA {
27371 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
27372 pub time_usec: u64,
27373 #[doc = "Latitude"]
27374 pub lat: i32,
27375 #[doc = "Longitude"]
27376 pub lon: i32,
27377 #[doc = "Altitude in meters above MSL"]
27378 pub alt: i32,
27379 #[doc = "Altitude above ground"]
27380 pub relative_alt: i32,
27381 #[doc = "Ground X Speed (Latitude)"]
27382 pub vx: f32,
27383 #[doc = "Ground Y Speed (Longitude)"]
27384 pub vy: f32,
27385 #[doc = "Ground Z Speed (Altitude)"]
27386 pub vz: f32,
27387 #[doc = "Row-major representation of a 6x6 position and velocity 6x6 cross-covariance matrix (states: lat, lon, alt, vx, vy, vz; first six entries are the first ROW, next six entries are the second row, etc.). If unknown, assign NaN value to first element in the array."]
27388 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27389 pub covariance: [f32; 36],
27390 #[doc = "Class id of the estimator this estimate originated from."]
27391 pub estimator_type: MavEstimatorType,
27392}
27393impl GLOBAL_POSITION_INT_COV_DATA {
27394 pub const ENCODED_LEN: usize = 181usize;
27395 pub const DEFAULT: Self = Self {
27396 time_usec: 0_u64,
27397 lat: 0_i32,
27398 lon: 0_i32,
27399 alt: 0_i32,
27400 relative_alt: 0_i32,
27401 vx: 0.0_f32,
27402 vy: 0.0_f32,
27403 vz: 0.0_f32,
27404 covariance: [0.0_f32; 36usize],
27405 estimator_type: MavEstimatorType::DEFAULT,
27406 };
27407 #[cfg(feature = "arbitrary")]
27408 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27409 use arbitrary::{Arbitrary, Unstructured};
27410 let mut buf = [0u8; 1024];
27411 rng.fill_bytes(&mut buf);
27412 let mut unstructured = Unstructured::new(&buf);
27413 Self::arbitrary(&mut unstructured).unwrap_or_default()
27414 }
27415}
27416impl Default for GLOBAL_POSITION_INT_COV_DATA {
27417 fn default() -> Self {
27418 Self::DEFAULT.clone()
27419 }
27420}
27421impl MessageData for GLOBAL_POSITION_INT_COV_DATA {
27422 type Message = MavMessage;
27423 const ID: u32 = 63u32;
27424 const NAME: &'static str = "GLOBAL_POSITION_INT_COV";
27425 const EXTRA_CRC: u8 = 119u8;
27426 const ENCODED_LEN: usize = 181usize;
27427 fn deser(
27428 _version: MavlinkVersion,
27429 __input: &[u8],
27430 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27431 let avail_len = __input.len();
27432 let mut payload_buf = [0; Self::ENCODED_LEN];
27433 let mut buf = if avail_len < Self::ENCODED_LEN {
27434 payload_buf[0..avail_len].copy_from_slice(__input);
27435 Bytes::new(&payload_buf)
27436 } else {
27437 Bytes::new(__input)
27438 };
27439 let mut __struct = Self::default();
27440 __struct.time_usec = buf.get_u64_le();
27441 __struct.lat = buf.get_i32_le();
27442 __struct.lon = buf.get_i32_le();
27443 __struct.alt = buf.get_i32_le();
27444 __struct.relative_alt = buf.get_i32_le();
27445 __struct.vx = buf.get_f32_le();
27446 __struct.vy = buf.get_f32_le();
27447 __struct.vz = buf.get_f32_le();
27448 for v in &mut __struct.covariance {
27449 let val = buf.get_f32_le();
27450 *v = val;
27451 }
27452 let tmp = buf.get_u8();
27453 __struct.estimator_type =
27454 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
27455 enum_type: "MavEstimatorType",
27456 value: tmp as u32,
27457 })?;
27458 Ok(__struct)
27459 }
27460 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27461 let mut __tmp = BytesMut::new(bytes);
27462 #[allow(clippy::absurd_extreme_comparisons)]
27463 #[allow(unused_comparisons)]
27464 if __tmp.remaining() < Self::ENCODED_LEN {
27465 panic!(
27466 "buffer is too small (need {} bytes, but got {})",
27467 Self::ENCODED_LEN,
27468 __tmp.remaining(),
27469 )
27470 }
27471 __tmp.put_u64_le(self.time_usec);
27472 __tmp.put_i32_le(self.lat);
27473 __tmp.put_i32_le(self.lon);
27474 __tmp.put_i32_le(self.alt);
27475 __tmp.put_i32_le(self.relative_alt);
27476 __tmp.put_f32_le(self.vx);
27477 __tmp.put_f32_le(self.vy);
27478 __tmp.put_f32_le(self.vz);
27479 for val in &self.covariance {
27480 __tmp.put_f32_le(*val);
27481 }
27482 __tmp.put_u8(self.estimator_type as u8);
27483 if matches!(version, MavlinkVersion::V2) {
27484 let len = __tmp.len();
27485 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27486 } else {
27487 __tmp.len()
27488 }
27489 }
27490}
27491#[doc = "id: 265"]
27492#[doc = "Orientation of a mount."]
27493#[derive(Debug, Clone, PartialEq)]
27494#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27495#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27496pub struct MOUNT_ORIENTATION_DATA {
27497 #[doc = "Timestamp (time since system boot)."]
27498 pub time_boot_ms: u32,
27499 #[doc = "Roll in global frame (set to NaN for invalid)."]
27500 pub roll: f32,
27501 #[doc = "Pitch in global frame (set to NaN for invalid)."]
27502 pub pitch: f32,
27503 #[doc = "Yaw relative to vehicle (set to NaN for invalid)."]
27504 pub yaw: f32,
27505 #[doc = "Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid)."]
27506 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27507 pub yaw_absolute: f32,
27508}
27509impl MOUNT_ORIENTATION_DATA {
27510 pub const ENCODED_LEN: usize = 20usize;
27511 pub const DEFAULT: Self = Self {
27512 time_boot_ms: 0_u32,
27513 roll: 0.0_f32,
27514 pitch: 0.0_f32,
27515 yaw: 0.0_f32,
27516 yaw_absolute: 0.0_f32,
27517 };
27518 #[cfg(feature = "arbitrary")]
27519 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27520 use arbitrary::{Arbitrary, Unstructured};
27521 let mut buf = [0u8; 1024];
27522 rng.fill_bytes(&mut buf);
27523 let mut unstructured = Unstructured::new(&buf);
27524 Self::arbitrary(&mut unstructured).unwrap_or_default()
27525 }
27526}
27527impl Default for MOUNT_ORIENTATION_DATA {
27528 fn default() -> Self {
27529 Self::DEFAULT.clone()
27530 }
27531}
27532impl MessageData for MOUNT_ORIENTATION_DATA {
27533 type Message = MavMessage;
27534 const ID: u32 = 265u32;
27535 const NAME: &'static str = "MOUNT_ORIENTATION";
27536 const EXTRA_CRC: u8 = 26u8;
27537 const ENCODED_LEN: usize = 20usize;
27538 fn deser(
27539 _version: MavlinkVersion,
27540 __input: &[u8],
27541 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27542 let avail_len = __input.len();
27543 let mut payload_buf = [0; Self::ENCODED_LEN];
27544 let mut buf = if avail_len < Self::ENCODED_LEN {
27545 payload_buf[0..avail_len].copy_from_slice(__input);
27546 Bytes::new(&payload_buf)
27547 } else {
27548 Bytes::new(__input)
27549 };
27550 let mut __struct = Self::default();
27551 __struct.time_boot_ms = buf.get_u32_le();
27552 __struct.roll = buf.get_f32_le();
27553 __struct.pitch = buf.get_f32_le();
27554 __struct.yaw = buf.get_f32_le();
27555 __struct.yaw_absolute = buf.get_f32_le();
27556 Ok(__struct)
27557 }
27558 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27559 let mut __tmp = BytesMut::new(bytes);
27560 #[allow(clippy::absurd_extreme_comparisons)]
27561 #[allow(unused_comparisons)]
27562 if __tmp.remaining() < Self::ENCODED_LEN {
27563 panic!(
27564 "buffer is too small (need {} bytes, but got {})",
27565 Self::ENCODED_LEN,
27566 __tmp.remaining(),
27567 )
27568 }
27569 __tmp.put_u32_le(self.time_boot_ms);
27570 __tmp.put_f32_le(self.roll);
27571 __tmp.put_f32_le(self.pitch);
27572 __tmp.put_f32_le(self.yaw);
27573 __tmp.put_f32_le(self.yaw_absolute);
27574 if matches!(version, MavlinkVersion::V2) {
27575 let len = __tmp.len();
27576 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27577 } else {
27578 __tmp.len()
27579 }
27580 }
27581}
27582#[doc = "id: 373"]
27583#[doc = "Telemetry of power generation system. Alternator or mechanical generator."]
27584#[derive(Debug, Clone, PartialEq)]
27585#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27586#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27587pub struct GENERATOR_STATUS_DATA {
27588 #[doc = "Status flags."]
27589 pub status: MavGeneratorStatusFlag,
27590 #[doc = "Current into/out of battery. Positive for out. Negative for in. NaN: field not provided."]
27591 pub battery_current: f32,
27592 #[doc = "Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided"]
27593 pub load_current: f32,
27594 #[doc = "The power being generated. NaN: field not provided"]
27595 pub power_generated: f32,
27596 #[doc = "Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus."]
27597 pub bus_voltage: f32,
27598 #[doc = "The target battery current. Positive for out. Negative for in. NaN: field not provided"]
27599 pub bat_current_setpoint: f32,
27600 #[doc = "Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided."]
27601 pub runtime: u32,
27602 #[doc = "Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided."]
27603 pub time_until_maintenance: i32,
27604 #[doc = "Speed of electrical generator or alternator. UINT16_MAX: field not provided."]
27605 pub generator_speed: u16,
27606 #[doc = "The temperature of the rectifier or power converter. INT16_MAX: field not provided."]
27607 pub rectifier_temperature: i16,
27608 #[doc = "The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided."]
27609 pub generator_temperature: i16,
27610}
27611impl GENERATOR_STATUS_DATA {
27612 pub const ENCODED_LEN: usize = 42usize;
27613 pub const DEFAULT: Self = Self {
27614 status: MavGeneratorStatusFlag::DEFAULT,
27615 battery_current: 0.0_f32,
27616 load_current: 0.0_f32,
27617 power_generated: 0.0_f32,
27618 bus_voltage: 0.0_f32,
27619 bat_current_setpoint: 0.0_f32,
27620 runtime: 0_u32,
27621 time_until_maintenance: 0_i32,
27622 generator_speed: 0_u16,
27623 rectifier_temperature: 0_i16,
27624 generator_temperature: 0_i16,
27625 };
27626 #[cfg(feature = "arbitrary")]
27627 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27628 use arbitrary::{Arbitrary, Unstructured};
27629 let mut buf = [0u8; 1024];
27630 rng.fill_bytes(&mut buf);
27631 let mut unstructured = Unstructured::new(&buf);
27632 Self::arbitrary(&mut unstructured).unwrap_or_default()
27633 }
27634}
27635impl Default for GENERATOR_STATUS_DATA {
27636 fn default() -> Self {
27637 Self::DEFAULT.clone()
27638 }
27639}
27640impl MessageData for GENERATOR_STATUS_DATA {
27641 type Message = MavMessage;
27642 const ID: u32 = 373u32;
27643 const NAME: &'static str = "GENERATOR_STATUS";
27644 const EXTRA_CRC: u8 = 117u8;
27645 const ENCODED_LEN: usize = 42usize;
27646 fn deser(
27647 _version: MavlinkVersion,
27648 __input: &[u8],
27649 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27650 let avail_len = __input.len();
27651 let mut payload_buf = [0; Self::ENCODED_LEN];
27652 let mut buf = if avail_len < Self::ENCODED_LEN {
27653 payload_buf[0..avail_len].copy_from_slice(__input);
27654 Bytes::new(&payload_buf)
27655 } else {
27656 Bytes::new(__input)
27657 };
27658 let mut __struct = Self::default();
27659 let tmp = buf.get_u64_le();
27660 __struct.status = MavGeneratorStatusFlag::from_bits(
27661 tmp & MavGeneratorStatusFlag::all().bits(),
27662 )
27663 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
27664 flag_type: "MavGeneratorStatusFlag",
27665 value: tmp as u32,
27666 })?;
27667 __struct.battery_current = buf.get_f32_le();
27668 __struct.load_current = buf.get_f32_le();
27669 __struct.power_generated = buf.get_f32_le();
27670 __struct.bus_voltage = buf.get_f32_le();
27671 __struct.bat_current_setpoint = buf.get_f32_le();
27672 __struct.runtime = buf.get_u32_le();
27673 __struct.time_until_maintenance = buf.get_i32_le();
27674 __struct.generator_speed = buf.get_u16_le();
27675 __struct.rectifier_temperature = buf.get_i16_le();
27676 __struct.generator_temperature = buf.get_i16_le();
27677 Ok(__struct)
27678 }
27679 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27680 let mut __tmp = BytesMut::new(bytes);
27681 #[allow(clippy::absurd_extreme_comparisons)]
27682 #[allow(unused_comparisons)]
27683 if __tmp.remaining() < Self::ENCODED_LEN {
27684 panic!(
27685 "buffer is too small (need {} bytes, but got {})",
27686 Self::ENCODED_LEN,
27687 __tmp.remaining(),
27688 )
27689 }
27690 __tmp.put_u64_le(self.status.bits());
27691 __tmp.put_f32_le(self.battery_current);
27692 __tmp.put_f32_le(self.load_current);
27693 __tmp.put_f32_le(self.power_generated);
27694 __tmp.put_f32_le(self.bus_voltage);
27695 __tmp.put_f32_le(self.bat_current_setpoint);
27696 __tmp.put_u32_le(self.runtime);
27697 __tmp.put_i32_le(self.time_until_maintenance);
27698 __tmp.put_u16_le(self.generator_speed);
27699 __tmp.put_i16_le(self.rectifier_temperature);
27700 __tmp.put_i16_le(self.generator_temperature);
27701 if matches!(version, MavlinkVersion::V2) {
27702 let len = __tmp.len();
27703 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27704 } else {
27705 __tmp.len()
27706 }
27707 }
27708}
27709#[doc = "id: 233"]
27710#[doc = "RTCM message for injecting into the onboard GPS (used for DGPS)."]
27711#[derive(Debug, Clone, PartialEq)]
27712#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27713#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27714pub struct GPS_RTCM_DATA_DATA {
27715 #[doc = "LSB: 1 means message is fragmented, next 2 bits are the fragment ID, the remaining 5 bits are used for the sequence ID. Messages are only to be flushed to the GPS when the entire message has been reconstructed on the autopilot. The fragment ID specifies which order the fragments should be assembled into a buffer, while the sequence ID is used to detect a mismatch between different buffers. The buffer is considered fully reconstructed when either all 4 fragments are present, or all the fragments before the first fragment with a non full payload is received. This management is used to ensure that normal GPS operation doesn't corrupt RTCM data, and to recover from a unreliable transport delivery order."]
27716 pub flags: u8,
27717 #[doc = "data length"]
27718 pub len: u8,
27719 #[doc = "RTCM message (may be fragmented)"]
27720 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27721 pub data: [u8; 180],
27722}
27723impl GPS_RTCM_DATA_DATA {
27724 pub const ENCODED_LEN: usize = 182usize;
27725 pub const DEFAULT: Self = Self {
27726 flags: 0_u8,
27727 len: 0_u8,
27728 data: [0_u8; 180usize],
27729 };
27730 #[cfg(feature = "arbitrary")]
27731 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27732 use arbitrary::{Arbitrary, Unstructured};
27733 let mut buf = [0u8; 1024];
27734 rng.fill_bytes(&mut buf);
27735 let mut unstructured = Unstructured::new(&buf);
27736 Self::arbitrary(&mut unstructured).unwrap_or_default()
27737 }
27738}
27739impl Default for GPS_RTCM_DATA_DATA {
27740 fn default() -> Self {
27741 Self::DEFAULT.clone()
27742 }
27743}
27744impl MessageData for GPS_RTCM_DATA_DATA {
27745 type Message = MavMessage;
27746 const ID: u32 = 233u32;
27747 const NAME: &'static str = "GPS_RTCM_DATA";
27748 const EXTRA_CRC: u8 = 35u8;
27749 const ENCODED_LEN: usize = 182usize;
27750 fn deser(
27751 _version: MavlinkVersion,
27752 __input: &[u8],
27753 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27754 let avail_len = __input.len();
27755 let mut payload_buf = [0; Self::ENCODED_LEN];
27756 let mut buf = if avail_len < Self::ENCODED_LEN {
27757 payload_buf[0..avail_len].copy_from_slice(__input);
27758 Bytes::new(&payload_buf)
27759 } else {
27760 Bytes::new(__input)
27761 };
27762 let mut __struct = Self::default();
27763 __struct.flags = buf.get_u8();
27764 __struct.len = buf.get_u8();
27765 for v in &mut __struct.data {
27766 let val = buf.get_u8();
27767 *v = val;
27768 }
27769 Ok(__struct)
27770 }
27771 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27772 let mut __tmp = BytesMut::new(bytes);
27773 #[allow(clippy::absurd_extreme_comparisons)]
27774 #[allow(unused_comparisons)]
27775 if __tmp.remaining() < Self::ENCODED_LEN {
27776 panic!(
27777 "buffer is too small (need {} bytes, but got {})",
27778 Self::ENCODED_LEN,
27779 __tmp.remaining(),
27780 )
27781 }
27782 __tmp.put_u8(self.flags);
27783 __tmp.put_u8(self.len);
27784 for val in &self.data {
27785 __tmp.put_u8(*val);
27786 }
27787 if matches!(version, MavlinkVersion::V2) {
27788 let len = __tmp.len();
27789 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27790 } else {
27791 __tmp.len()
27792 }
27793 }
27794}
27795#[doc = "id: 62"]
27796#[doc = "The state of the navigation and position controller."]
27797#[derive(Debug, Clone, PartialEq)]
27798#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27799#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27800pub struct NAV_CONTROLLER_OUTPUT_DATA {
27801 #[doc = "Current desired roll"]
27802 pub nav_roll: f32,
27803 #[doc = "Current desired pitch"]
27804 pub nav_pitch: f32,
27805 #[doc = "Current altitude error"]
27806 pub alt_error: f32,
27807 #[doc = "Current airspeed error"]
27808 pub aspd_error: f32,
27809 #[doc = "Current crosstrack error on x-y plane"]
27810 pub xtrack_error: f32,
27811 #[doc = "Current desired heading"]
27812 pub nav_bearing: i16,
27813 #[doc = "Bearing to current waypoint/target"]
27814 pub target_bearing: i16,
27815 #[doc = "Distance to active waypoint"]
27816 pub wp_dist: u16,
27817}
27818impl NAV_CONTROLLER_OUTPUT_DATA {
27819 pub const ENCODED_LEN: usize = 26usize;
27820 pub const DEFAULT: Self = Self {
27821 nav_roll: 0.0_f32,
27822 nav_pitch: 0.0_f32,
27823 alt_error: 0.0_f32,
27824 aspd_error: 0.0_f32,
27825 xtrack_error: 0.0_f32,
27826 nav_bearing: 0_i16,
27827 target_bearing: 0_i16,
27828 wp_dist: 0_u16,
27829 };
27830 #[cfg(feature = "arbitrary")]
27831 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27832 use arbitrary::{Arbitrary, Unstructured};
27833 let mut buf = [0u8; 1024];
27834 rng.fill_bytes(&mut buf);
27835 let mut unstructured = Unstructured::new(&buf);
27836 Self::arbitrary(&mut unstructured).unwrap_or_default()
27837 }
27838}
27839impl Default for NAV_CONTROLLER_OUTPUT_DATA {
27840 fn default() -> Self {
27841 Self::DEFAULT.clone()
27842 }
27843}
27844impl MessageData for NAV_CONTROLLER_OUTPUT_DATA {
27845 type Message = MavMessage;
27846 const ID: u32 = 62u32;
27847 const NAME: &'static str = "NAV_CONTROLLER_OUTPUT";
27848 const EXTRA_CRC: u8 = 183u8;
27849 const ENCODED_LEN: usize = 26usize;
27850 fn deser(
27851 _version: MavlinkVersion,
27852 __input: &[u8],
27853 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27854 let avail_len = __input.len();
27855 let mut payload_buf = [0; Self::ENCODED_LEN];
27856 let mut buf = if avail_len < Self::ENCODED_LEN {
27857 payload_buf[0..avail_len].copy_from_slice(__input);
27858 Bytes::new(&payload_buf)
27859 } else {
27860 Bytes::new(__input)
27861 };
27862 let mut __struct = Self::default();
27863 __struct.nav_roll = buf.get_f32_le();
27864 __struct.nav_pitch = buf.get_f32_le();
27865 __struct.alt_error = buf.get_f32_le();
27866 __struct.aspd_error = buf.get_f32_le();
27867 __struct.xtrack_error = buf.get_f32_le();
27868 __struct.nav_bearing = buf.get_i16_le();
27869 __struct.target_bearing = buf.get_i16_le();
27870 __struct.wp_dist = buf.get_u16_le();
27871 Ok(__struct)
27872 }
27873 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27874 let mut __tmp = BytesMut::new(bytes);
27875 #[allow(clippy::absurd_extreme_comparisons)]
27876 #[allow(unused_comparisons)]
27877 if __tmp.remaining() < Self::ENCODED_LEN {
27878 panic!(
27879 "buffer is too small (need {} bytes, but got {})",
27880 Self::ENCODED_LEN,
27881 __tmp.remaining(),
27882 )
27883 }
27884 __tmp.put_f32_le(self.nav_roll);
27885 __tmp.put_f32_le(self.nav_pitch);
27886 __tmp.put_f32_le(self.alt_error);
27887 __tmp.put_f32_le(self.aspd_error);
27888 __tmp.put_f32_le(self.xtrack_error);
27889 __tmp.put_i16_le(self.nav_bearing);
27890 __tmp.put_i16_le(self.target_bearing);
27891 __tmp.put_u16_le(self.wp_dist);
27892 if matches!(version, MavlinkVersion::V2) {
27893 let len = __tmp.len();
27894 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
27895 } else {
27896 __tmp.len()
27897 }
27898 }
27899}
27900#[doc = "id: 101"]
27901#[doc = "Global position/attitude estimate from a vision source."]
27902#[derive(Debug, Clone, PartialEq)]
27903#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
27904#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
27905pub struct GLOBAL_VISION_POSITION_ESTIMATE_DATA {
27906 #[doc = "Timestamp (UNIX time or since system boot)"]
27907 pub usec: u64,
27908 #[doc = "Global X position"]
27909 pub x: f32,
27910 #[doc = "Global Y position"]
27911 pub y: f32,
27912 #[doc = "Global Z position"]
27913 pub z: f32,
27914 #[doc = "Roll angle"]
27915 pub roll: f32,
27916 #[doc = "Pitch angle"]
27917 pub pitch: f32,
27918 #[doc = "Yaw angle"]
27919 pub yaw: f32,
27920 #[doc = "Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array."]
27921 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27922 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
27923 pub covariance: [f32; 21],
27924 #[doc = "Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps."]
27925 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
27926 pub reset_counter: u8,
27927}
27928impl GLOBAL_VISION_POSITION_ESTIMATE_DATA {
27929 pub const ENCODED_LEN: usize = 117usize;
27930 pub const DEFAULT: Self = Self {
27931 usec: 0_u64,
27932 x: 0.0_f32,
27933 y: 0.0_f32,
27934 z: 0.0_f32,
27935 roll: 0.0_f32,
27936 pitch: 0.0_f32,
27937 yaw: 0.0_f32,
27938 covariance: [0.0_f32; 21usize],
27939 reset_counter: 0_u8,
27940 };
27941 #[cfg(feature = "arbitrary")]
27942 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
27943 use arbitrary::{Arbitrary, Unstructured};
27944 let mut buf = [0u8; 1024];
27945 rng.fill_bytes(&mut buf);
27946 let mut unstructured = Unstructured::new(&buf);
27947 Self::arbitrary(&mut unstructured).unwrap_or_default()
27948 }
27949}
27950impl Default for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
27951 fn default() -> Self {
27952 Self::DEFAULT.clone()
27953 }
27954}
27955impl MessageData for GLOBAL_VISION_POSITION_ESTIMATE_DATA {
27956 type Message = MavMessage;
27957 const ID: u32 = 101u32;
27958 const NAME: &'static str = "GLOBAL_VISION_POSITION_ESTIMATE";
27959 const EXTRA_CRC: u8 = 102u8;
27960 const ENCODED_LEN: usize = 117usize;
27961 fn deser(
27962 _version: MavlinkVersion,
27963 __input: &[u8],
27964 ) -> Result<Self, ::mavlink_core::error::ParserError> {
27965 let avail_len = __input.len();
27966 let mut payload_buf = [0; Self::ENCODED_LEN];
27967 let mut buf = if avail_len < Self::ENCODED_LEN {
27968 payload_buf[0..avail_len].copy_from_slice(__input);
27969 Bytes::new(&payload_buf)
27970 } else {
27971 Bytes::new(__input)
27972 };
27973 let mut __struct = Self::default();
27974 __struct.usec = buf.get_u64_le();
27975 __struct.x = buf.get_f32_le();
27976 __struct.y = buf.get_f32_le();
27977 __struct.z = buf.get_f32_le();
27978 __struct.roll = buf.get_f32_le();
27979 __struct.pitch = buf.get_f32_le();
27980 __struct.yaw = buf.get_f32_le();
27981 for v in &mut __struct.covariance {
27982 let val = buf.get_f32_le();
27983 *v = val;
27984 }
27985 __struct.reset_counter = buf.get_u8();
27986 Ok(__struct)
27987 }
27988 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
27989 let mut __tmp = BytesMut::new(bytes);
27990 #[allow(clippy::absurd_extreme_comparisons)]
27991 #[allow(unused_comparisons)]
27992 if __tmp.remaining() < Self::ENCODED_LEN {
27993 panic!(
27994 "buffer is too small (need {} bytes, but got {})",
27995 Self::ENCODED_LEN,
27996 __tmp.remaining(),
27997 )
27998 }
27999 __tmp.put_u64_le(self.usec);
28000 __tmp.put_f32_le(self.x);
28001 __tmp.put_f32_le(self.y);
28002 __tmp.put_f32_le(self.z);
28003 __tmp.put_f32_le(self.roll);
28004 __tmp.put_f32_le(self.pitch);
28005 __tmp.put_f32_le(self.yaw);
28006 for val in &self.covariance {
28007 __tmp.put_f32_le(*val);
28008 }
28009 __tmp.put_u8(self.reset_counter);
28010 if matches!(version, MavlinkVersion::V2) {
28011 let len = __tmp.len();
28012 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28013 } else {
28014 __tmp.len()
28015 }
28016 }
28017}
28018#[doc = "id: 322"]
28019#[doc = "Emit the value of a parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows them to re-request missing parameters after a loss or timeout."]
28020#[derive(Debug, Clone, PartialEq)]
28021#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28022#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28023pub struct PARAM_EXT_VALUE_DATA {
28024 #[doc = "Total number of parameters"]
28025 pub param_count: u16,
28026 #[doc = "Index of this parameter"]
28027 pub param_index: u16,
28028 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
28029 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28030 pub param_id: [u8; 16],
28031 #[doc = "Parameter value"]
28032 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
28033 pub param_value: [u8; 128],
28034 #[doc = "Parameter type."]
28035 pub param_type: MavParamExtType,
28036}
28037impl PARAM_EXT_VALUE_DATA {
28038 pub const ENCODED_LEN: usize = 149usize;
28039 pub const DEFAULT: Self = Self {
28040 param_count: 0_u16,
28041 param_index: 0_u16,
28042 param_id: [0_u8; 16usize],
28043 param_value: [0_u8; 128usize],
28044 param_type: MavParamExtType::DEFAULT,
28045 };
28046 #[cfg(feature = "arbitrary")]
28047 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28048 use arbitrary::{Arbitrary, Unstructured};
28049 let mut buf = [0u8; 1024];
28050 rng.fill_bytes(&mut buf);
28051 let mut unstructured = Unstructured::new(&buf);
28052 Self::arbitrary(&mut unstructured).unwrap_or_default()
28053 }
28054}
28055impl Default for PARAM_EXT_VALUE_DATA {
28056 fn default() -> Self {
28057 Self::DEFAULT.clone()
28058 }
28059}
28060impl MessageData for PARAM_EXT_VALUE_DATA {
28061 type Message = MavMessage;
28062 const ID: u32 = 322u32;
28063 const NAME: &'static str = "PARAM_EXT_VALUE";
28064 const EXTRA_CRC: u8 = 243u8;
28065 const ENCODED_LEN: usize = 149usize;
28066 fn deser(
28067 _version: MavlinkVersion,
28068 __input: &[u8],
28069 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28070 let avail_len = __input.len();
28071 let mut payload_buf = [0; Self::ENCODED_LEN];
28072 let mut buf = if avail_len < Self::ENCODED_LEN {
28073 payload_buf[0..avail_len].copy_from_slice(__input);
28074 Bytes::new(&payload_buf)
28075 } else {
28076 Bytes::new(__input)
28077 };
28078 let mut __struct = Self::default();
28079 __struct.param_count = buf.get_u16_le();
28080 __struct.param_index = buf.get_u16_le();
28081 for v in &mut __struct.param_id {
28082 let val = buf.get_u8();
28083 *v = val;
28084 }
28085 for v in &mut __struct.param_value {
28086 let val = buf.get_u8();
28087 *v = val;
28088 }
28089 let tmp = buf.get_u8();
28090 __struct.param_type =
28091 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28092 enum_type: "MavParamExtType",
28093 value: tmp as u32,
28094 })?;
28095 Ok(__struct)
28096 }
28097 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28098 let mut __tmp = BytesMut::new(bytes);
28099 #[allow(clippy::absurd_extreme_comparisons)]
28100 #[allow(unused_comparisons)]
28101 if __tmp.remaining() < Self::ENCODED_LEN {
28102 panic!(
28103 "buffer is too small (need {} bytes, but got {})",
28104 Self::ENCODED_LEN,
28105 __tmp.remaining(),
28106 )
28107 }
28108 __tmp.put_u16_le(self.param_count);
28109 __tmp.put_u16_le(self.param_index);
28110 for val in &self.param_id {
28111 __tmp.put_u8(*val);
28112 }
28113 for val in &self.param_value {
28114 __tmp.put_u8(*val);
28115 }
28116 __tmp.put_u8(self.param_type as u8);
28117 if matches!(version, MavlinkVersion::V2) {
28118 let len = __tmp.len();
28119 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28120 } else {
28121 __tmp.len()
28122 }
28123 }
28124}
28125#[doc = "id: 262"]
28126#[doc = "Information about the status of a capture. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
28127#[derive(Debug, Clone, PartialEq)]
28128#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28129#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28130pub struct CAMERA_CAPTURE_STATUS_DATA {
28131 #[doc = "Timestamp (time since system boot)."]
28132 pub time_boot_ms: u32,
28133 #[doc = "Image capture interval"]
28134 pub image_interval: f32,
28135 #[doc = "Elapsed time since recording started (0: Not supported/available). A GCS should compute recording time and use non-zero values of this field to correct any discrepancy."]
28136 pub recording_time_ms: u32,
28137 #[doc = "Available storage capacity."]
28138 pub available_capacity: f32,
28139 #[doc = "Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)"]
28140 pub image_status: u8,
28141 #[doc = "Current status of video capturing (0: idle, 1: capture in progress)"]
28142 pub video_status: u8,
28143 #[doc = "Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT)."]
28144 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28145 pub image_count: i32,
28146 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
28147 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28148 pub camera_device_id: u8,
28149}
28150impl CAMERA_CAPTURE_STATUS_DATA {
28151 pub const ENCODED_LEN: usize = 23usize;
28152 pub const DEFAULT: Self = Self {
28153 time_boot_ms: 0_u32,
28154 image_interval: 0.0_f32,
28155 recording_time_ms: 0_u32,
28156 available_capacity: 0.0_f32,
28157 image_status: 0_u8,
28158 video_status: 0_u8,
28159 image_count: 0_i32,
28160 camera_device_id: 0_u8,
28161 };
28162 #[cfg(feature = "arbitrary")]
28163 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28164 use arbitrary::{Arbitrary, Unstructured};
28165 let mut buf = [0u8; 1024];
28166 rng.fill_bytes(&mut buf);
28167 let mut unstructured = Unstructured::new(&buf);
28168 Self::arbitrary(&mut unstructured).unwrap_or_default()
28169 }
28170}
28171impl Default for CAMERA_CAPTURE_STATUS_DATA {
28172 fn default() -> Self {
28173 Self::DEFAULT.clone()
28174 }
28175}
28176impl MessageData for CAMERA_CAPTURE_STATUS_DATA {
28177 type Message = MavMessage;
28178 const ID: u32 = 262u32;
28179 const NAME: &'static str = "CAMERA_CAPTURE_STATUS";
28180 const EXTRA_CRC: u8 = 12u8;
28181 const ENCODED_LEN: usize = 23usize;
28182 fn deser(
28183 _version: MavlinkVersion,
28184 __input: &[u8],
28185 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28186 let avail_len = __input.len();
28187 let mut payload_buf = [0; Self::ENCODED_LEN];
28188 let mut buf = if avail_len < Self::ENCODED_LEN {
28189 payload_buf[0..avail_len].copy_from_slice(__input);
28190 Bytes::new(&payload_buf)
28191 } else {
28192 Bytes::new(__input)
28193 };
28194 let mut __struct = Self::default();
28195 __struct.time_boot_ms = buf.get_u32_le();
28196 __struct.image_interval = buf.get_f32_le();
28197 __struct.recording_time_ms = buf.get_u32_le();
28198 __struct.available_capacity = buf.get_f32_le();
28199 __struct.image_status = buf.get_u8();
28200 __struct.video_status = buf.get_u8();
28201 __struct.image_count = buf.get_i32_le();
28202 __struct.camera_device_id = buf.get_u8();
28203 Ok(__struct)
28204 }
28205 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28206 let mut __tmp = BytesMut::new(bytes);
28207 #[allow(clippy::absurd_extreme_comparisons)]
28208 #[allow(unused_comparisons)]
28209 if __tmp.remaining() < Self::ENCODED_LEN {
28210 panic!(
28211 "buffer is too small (need {} bytes, but got {})",
28212 Self::ENCODED_LEN,
28213 __tmp.remaining(),
28214 )
28215 }
28216 __tmp.put_u32_le(self.time_boot_ms);
28217 __tmp.put_f32_le(self.image_interval);
28218 __tmp.put_u32_le(self.recording_time_ms);
28219 __tmp.put_f32_le(self.available_capacity);
28220 __tmp.put_u8(self.image_status);
28221 __tmp.put_u8(self.video_status);
28222 __tmp.put_i32_le(self.image_count);
28223 __tmp.put_u8(self.camera_device_id);
28224 if matches!(version, MavlinkVersion::V2) {
28225 let len = __tmp.len();
28226 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28227 } else {
28228 __tmp.len()
28229 }
28230 }
28231}
28232#[doc = "id: 288"]
28233#[doc = "High level message to control a gimbal manually. The angles or angular rates are unitless; the actual rates will depend on internal gimbal manager settings/configuration (e.g. set by parameters). This message is to be sent to the gimbal manager (e.g. from a ground station). Angles and rates can be set to NaN according to use case."]
28234#[derive(Debug, Clone, PartialEq)]
28235#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28236#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28237pub struct GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
28238 #[doc = "High level gimbal manager flags."]
28239 pub flags: GimbalManagerFlags,
28240 #[doc = "Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
28241 pub pitch: f32,
28242 #[doc = "Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
28243 pub yaw: f32,
28244 #[doc = "Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored)."]
28245 pub pitch_rate: f32,
28246 #[doc = "Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored)."]
28247 pub yaw_rate: f32,
28248 #[doc = "System ID"]
28249 pub target_system: u8,
28250 #[doc = "Component ID"]
28251 pub target_component: u8,
28252 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
28253 pub gimbal_device_id: u8,
28254}
28255impl GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
28256 pub const ENCODED_LEN: usize = 23usize;
28257 pub const DEFAULT: Self = Self {
28258 flags: GimbalManagerFlags::DEFAULT,
28259 pitch: 0.0_f32,
28260 yaw: 0.0_f32,
28261 pitch_rate: 0.0_f32,
28262 yaw_rate: 0.0_f32,
28263 target_system: 0_u8,
28264 target_component: 0_u8,
28265 gimbal_device_id: 0_u8,
28266 };
28267 #[cfg(feature = "arbitrary")]
28268 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28269 use arbitrary::{Arbitrary, Unstructured};
28270 let mut buf = [0u8; 1024];
28271 rng.fill_bytes(&mut buf);
28272 let mut unstructured = Unstructured::new(&buf);
28273 Self::arbitrary(&mut unstructured).unwrap_or_default()
28274 }
28275}
28276impl Default for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
28277 fn default() -> Self {
28278 Self::DEFAULT.clone()
28279 }
28280}
28281impl MessageData for GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA {
28282 type Message = MavMessage;
28283 const ID: u32 = 288u32;
28284 const NAME: &'static str = "GIMBAL_MANAGER_SET_MANUAL_CONTROL";
28285 const EXTRA_CRC: u8 = 20u8;
28286 const ENCODED_LEN: usize = 23usize;
28287 fn deser(
28288 _version: MavlinkVersion,
28289 __input: &[u8],
28290 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28291 let avail_len = __input.len();
28292 let mut payload_buf = [0; Self::ENCODED_LEN];
28293 let mut buf = if avail_len < Self::ENCODED_LEN {
28294 payload_buf[0..avail_len].copy_from_slice(__input);
28295 Bytes::new(&payload_buf)
28296 } else {
28297 Bytes::new(__input)
28298 };
28299 let mut __struct = Self::default();
28300 let tmp = buf.get_u32_le();
28301 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
28302 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28303 flag_type: "GimbalManagerFlags",
28304 value: tmp as u32,
28305 })?;
28306 __struct.pitch = buf.get_f32_le();
28307 __struct.yaw = buf.get_f32_le();
28308 __struct.pitch_rate = buf.get_f32_le();
28309 __struct.yaw_rate = buf.get_f32_le();
28310 __struct.target_system = buf.get_u8();
28311 __struct.target_component = buf.get_u8();
28312 __struct.gimbal_device_id = buf.get_u8();
28313 Ok(__struct)
28314 }
28315 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28316 let mut __tmp = BytesMut::new(bytes);
28317 #[allow(clippy::absurd_extreme_comparisons)]
28318 #[allow(unused_comparisons)]
28319 if __tmp.remaining() < Self::ENCODED_LEN {
28320 panic!(
28321 "buffer is too small (need {} bytes, but got {})",
28322 Self::ENCODED_LEN,
28323 __tmp.remaining(),
28324 )
28325 }
28326 __tmp.put_u32_le(self.flags.bits());
28327 __tmp.put_f32_le(self.pitch);
28328 __tmp.put_f32_le(self.yaw);
28329 __tmp.put_f32_le(self.pitch_rate);
28330 __tmp.put_f32_le(self.yaw_rate);
28331 __tmp.put_u8(self.target_system);
28332 __tmp.put_u8(self.target_component);
28333 __tmp.put_u8(self.gimbal_device_id);
28334 if matches!(version, MavlinkVersion::V2) {
28335 let len = __tmp.len();
28336 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28337 } else {
28338 __tmp.len()
28339 }
28340 }
28341}
28342#[doc = "id: 280"]
28343#[doc = "Information about a high level gimbal manager. This message should be requested by a ground station using MAV_CMD_REQUEST_MESSAGE."]
28344#[derive(Debug, Clone, PartialEq)]
28345#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28346#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28347pub struct GIMBAL_MANAGER_INFORMATION_DATA {
28348 #[doc = "Timestamp (time since system boot)."]
28349 pub time_boot_ms: u32,
28350 #[doc = "Bitmap of gimbal capability flags."]
28351 pub cap_flags: GimbalManagerCapFlags,
28352 #[doc = "Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
28353 pub roll_min: f32,
28354 #[doc = "Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)"]
28355 pub roll_max: f32,
28356 #[doc = "Minimum pitch angle (positive: up, negative: down)"]
28357 pub pitch_min: f32,
28358 #[doc = "Maximum pitch angle (positive: up, negative: down)"]
28359 pub pitch_max: f32,
28360 #[doc = "Minimum yaw angle (positive: to the right, negative: to the left)"]
28361 pub yaw_min: f32,
28362 #[doc = "Maximum yaw angle (positive: to the right, negative: to the left)"]
28363 pub yaw_max: f32,
28364 #[doc = "Gimbal device ID that this gimbal manager is responsible for. Component ID of gimbal device (or 1-6 for non-MAVLink gimbal)."]
28365 pub gimbal_device_id: u8,
28366}
28367impl GIMBAL_MANAGER_INFORMATION_DATA {
28368 pub const ENCODED_LEN: usize = 33usize;
28369 pub const DEFAULT: Self = Self {
28370 time_boot_ms: 0_u32,
28371 cap_flags: GimbalManagerCapFlags::DEFAULT,
28372 roll_min: 0.0_f32,
28373 roll_max: 0.0_f32,
28374 pitch_min: 0.0_f32,
28375 pitch_max: 0.0_f32,
28376 yaw_min: 0.0_f32,
28377 yaw_max: 0.0_f32,
28378 gimbal_device_id: 0_u8,
28379 };
28380 #[cfg(feature = "arbitrary")]
28381 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28382 use arbitrary::{Arbitrary, Unstructured};
28383 let mut buf = [0u8; 1024];
28384 rng.fill_bytes(&mut buf);
28385 let mut unstructured = Unstructured::new(&buf);
28386 Self::arbitrary(&mut unstructured).unwrap_or_default()
28387 }
28388}
28389impl Default for GIMBAL_MANAGER_INFORMATION_DATA {
28390 fn default() -> Self {
28391 Self::DEFAULT.clone()
28392 }
28393}
28394impl MessageData for GIMBAL_MANAGER_INFORMATION_DATA {
28395 type Message = MavMessage;
28396 const ID: u32 = 280u32;
28397 const NAME: &'static str = "GIMBAL_MANAGER_INFORMATION";
28398 const EXTRA_CRC: u8 = 70u8;
28399 const ENCODED_LEN: usize = 33usize;
28400 fn deser(
28401 _version: MavlinkVersion,
28402 __input: &[u8],
28403 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28404 let avail_len = __input.len();
28405 let mut payload_buf = [0; Self::ENCODED_LEN];
28406 let mut buf = if avail_len < Self::ENCODED_LEN {
28407 payload_buf[0..avail_len].copy_from_slice(__input);
28408 Bytes::new(&payload_buf)
28409 } else {
28410 Bytes::new(__input)
28411 };
28412 let mut __struct = Self::default();
28413 __struct.time_boot_ms = buf.get_u32_le();
28414 let tmp = buf.get_u32_le();
28415 __struct.cap_flags = GimbalManagerCapFlags::from_bits(
28416 tmp & GimbalManagerCapFlags::all().bits(),
28417 )
28418 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28419 flag_type: "GimbalManagerCapFlags",
28420 value: tmp as u32,
28421 })?;
28422 __struct.roll_min = buf.get_f32_le();
28423 __struct.roll_max = buf.get_f32_le();
28424 __struct.pitch_min = buf.get_f32_le();
28425 __struct.pitch_max = buf.get_f32_le();
28426 __struct.yaw_min = buf.get_f32_le();
28427 __struct.yaw_max = buf.get_f32_le();
28428 __struct.gimbal_device_id = buf.get_u8();
28429 Ok(__struct)
28430 }
28431 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28432 let mut __tmp = BytesMut::new(bytes);
28433 #[allow(clippy::absurd_extreme_comparisons)]
28434 #[allow(unused_comparisons)]
28435 if __tmp.remaining() < Self::ENCODED_LEN {
28436 panic!(
28437 "buffer is too small (need {} bytes, but got {})",
28438 Self::ENCODED_LEN,
28439 __tmp.remaining(),
28440 )
28441 }
28442 __tmp.put_u32_le(self.time_boot_ms);
28443 __tmp.put_u32_le(self.cap_flags.bits());
28444 __tmp.put_f32_le(self.roll_min);
28445 __tmp.put_f32_le(self.roll_max);
28446 __tmp.put_f32_le(self.pitch_min);
28447 __tmp.put_f32_le(self.pitch_max);
28448 __tmp.put_f32_le(self.yaw_min);
28449 __tmp.put_f32_le(self.yaw_max);
28450 __tmp.put_u8(self.gimbal_device_id);
28451 if matches!(version, MavlinkVersion::V2) {
28452 let len = __tmp.len();
28453 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28454 } else {
28455 __tmp.len()
28456 }
28457 }
28458}
28459#[doc = "id: 235"]
28460#[doc = "Message appropriate for high latency connections like Iridium (version 2)."]
28461#[derive(Debug, Clone, PartialEq)]
28462#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28463#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28464pub struct HIGH_LATENCY2_DATA {
28465 #[doc = "Timestamp (milliseconds since boot or Unix epoch)"]
28466 pub timestamp: u32,
28467 #[doc = "Latitude"]
28468 pub latitude: i32,
28469 #[doc = "Longitude"]
28470 pub longitude: i32,
28471 #[doc = "A bitfield for use for autopilot-specific flags (2 byte version)."]
28472 pub custom_mode: u16,
28473 #[doc = "Altitude above mean sea level"]
28474 pub altitude: i16,
28475 #[doc = "Altitude setpoint"]
28476 pub target_altitude: i16,
28477 #[doc = "Distance to target waypoint or position"]
28478 pub target_distance: u16,
28479 #[doc = "Current waypoint number"]
28480 pub wp_num: u16,
28481 #[doc = "Bitmap of failure flags."]
28482 pub failure_flags: HlFailureFlag,
28483 #[doc = "Type of the MAV (quadrotor, helicopter, etc.)"]
28484 pub mavtype: MavType,
28485 #[doc = "Autopilot type / class. Use MAV_AUTOPILOT_INVALID for components that are not flight controllers."]
28486 pub autopilot: MavAutopilot,
28487 #[doc = "Heading"]
28488 pub heading: u8,
28489 #[doc = "Heading setpoint"]
28490 pub target_heading: u8,
28491 #[doc = "Throttle"]
28492 pub throttle: u8,
28493 #[doc = "Airspeed"]
28494 pub airspeed: u8,
28495 #[doc = "Airspeed setpoint"]
28496 pub airspeed_sp: u8,
28497 #[doc = "Groundspeed"]
28498 pub groundspeed: u8,
28499 #[doc = "Windspeed"]
28500 pub windspeed: u8,
28501 #[doc = "Wind heading"]
28502 pub wind_heading: u8,
28503 #[doc = "Maximum error horizontal position since last message"]
28504 pub eph: u8,
28505 #[doc = "Maximum error vertical position since last message"]
28506 pub epv: u8,
28507 #[doc = "Air temperature"]
28508 pub temperature_air: i8,
28509 #[doc = "Maximum climb rate magnitude since last message"]
28510 pub climb_rate: i8,
28511 #[doc = "Battery level (-1 if field not provided)."]
28512 pub battery: i8,
28513 #[doc = "Field for custom payload."]
28514 pub custom0: i8,
28515 #[doc = "Field for custom payload."]
28516 pub custom1: i8,
28517 #[doc = "Field for custom payload."]
28518 pub custom2: i8,
28519}
28520impl HIGH_LATENCY2_DATA {
28521 pub const ENCODED_LEN: usize = 42usize;
28522 pub const DEFAULT: Self = Self {
28523 timestamp: 0_u32,
28524 latitude: 0_i32,
28525 longitude: 0_i32,
28526 custom_mode: 0_u16,
28527 altitude: 0_i16,
28528 target_altitude: 0_i16,
28529 target_distance: 0_u16,
28530 wp_num: 0_u16,
28531 failure_flags: HlFailureFlag::DEFAULT,
28532 mavtype: MavType::DEFAULT,
28533 autopilot: MavAutopilot::DEFAULT,
28534 heading: 0_u8,
28535 target_heading: 0_u8,
28536 throttle: 0_u8,
28537 airspeed: 0_u8,
28538 airspeed_sp: 0_u8,
28539 groundspeed: 0_u8,
28540 windspeed: 0_u8,
28541 wind_heading: 0_u8,
28542 eph: 0_u8,
28543 epv: 0_u8,
28544 temperature_air: 0_i8,
28545 climb_rate: 0_i8,
28546 battery: 0_i8,
28547 custom0: 0_i8,
28548 custom1: 0_i8,
28549 custom2: 0_i8,
28550 };
28551 #[cfg(feature = "arbitrary")]
28552 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28553 use arbitrary::{Arbitrary, Unstructured};
28554 let mut buf = [0u8; 1024];
28555 rng.fill_bytes(&mut buf);
28556 let mut unstructured = Unstructured::new(&buf);
28557 Self::arbitrary(&mut unstructured).unwrap_or_default()
28558 }
28559}
28560impl Default for HIGH_LATENCY2_DATA {
28561 fn default() -> Self {
28562 Self::DEFAULT.clone()
28563 }
28564}
28565impl MessageData for HIGH_LATENCY2_DATA {
28566 type Message = MavMessage;
28567 const ID: u32 = 235u32;
28568 const NAME: &'static str = "HIGH_LATENCY2";
28569 const EXTRA_CRC: u8 = 179u8;
28570 const ENCODED_LEN: usize = 42usize;
28571 fn deser(
28572 _version: MavlinkVersion,
28573 __input: &[u8],
28574 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28575 let avail_len = __input.len();
28576 let mut payload_buf = [0; Self::ENCODED_LEN];
28577 let mut buf = if avail_len < Self::ENCODED_LEN {
28578 payload_buf[0..avail_len].copy_from_slice(__input);
28579 Bytes::new(&payload_buf)
28580 } else {
28581 Bytes::new(__input)
28582 };
28583 let mut __struct = Self::default();
28584 __struct.timestamp = buf.get_u32_le();
28585 __struct.latitude = buf.get_i32_le();
28586 __struct.longitude = buf.get_i32_le();
28587 __struct.custom_mode = buf.get_u16_le();
28588 __struct.altitude = buf.get_i16_le();
28589 __struct.target_altitude = buf.get_i16_le();
28590 __struct.target_distance = buf.get_u16_le();
28591 __struct.wp_num = buf.get_u16_le();
28592 let tmp = buf.get_u16_le();
28593 __struct.failure_flags = HlFailureFlag::from_bits(tmp & HlFailureFlag::all().bits())
28594 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28595 flag_type: "HlFailureFlag",
28596 value: tmp as u32,
28597 })?;
28598 let tmp = buf.get_u8();
28599 __struct.mavtype =
28600 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28601 enum_type: "MavType",
28602 value: tmp as u32,
28603 })?;
28604 let tmp = buf.get_u8();
28605 __struct.autopilot =
28606 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28607 enum_type: "MavAutopilot",
28608 value: tmp as u32,
28609 })?;
28610 __struct.heading = buf.get_u8();
28611 __struct.target_heading = buf.get_u8();
28612 __struct.throttle = buf.get_u8();
28613 __struct.airspeed = buf.get_u8();
28614 __struct.airspeed_sp = buf.get_u8();
28615 __struct.groundspeed = buf.get_u8();
28616 __struct.windspeed = buf.get_u8();
28617 __struct.wind_heading = buf.get_u8();
28618 __struct.eph = buf.get_u8();
28619 __struct.epv = buf.get_u8();
28620 __struct.temperature_air = buf.get_i8();
28621 __struct.climb_rate = buf.get_i8();
28622 __struct.battery = buf.get_i8();
28623 __struct.custom0 = buf.get_i8();
28624 __struct.custom1 = buf.get_i8();
28625 __struct.custom2 = buf.get_i8();
28626 Ok(__struct)
28627 }
28628 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28629 let mut __tmp = BytesMut::new(bytes);
28630 #[allow(clippy::absurd_extreme_comparisons)]
28631 #[allow(unused_comparisons)]
28632 if __tmp.remaining() < Self::ENCODED_LEN {
28633 panic!(
28634 "buffer is too small (need {} bytes, but got {})",
28635 Self::ENCODED_LEN,
28636 __tmp.remaining(),
28637 )
28638 }
28639 __tmp.put_u32_le(self.timestamp);
28640 __tmp.put_i32_le(self.latitude);
28641 __tmp.put_i32_le(self.longitude);
28642 __tmp.put_u16_le(self.custom_mode);
28643 __tmp.put_i16_le(self.altitude);
28644 __tmp.put_i16_le(self.target_altitude);
28645 __tmp.put_u16_le(self.target_distance);
28646 __tmp.put_u16_le(self.wp_num);
28647 __tmp.put_u16_le(self.failure_flags.bits());
28648 __tmp.put_u8(self.mavtype as u8);
28649 __tmp.put_u8(self.autopilot as u8);
28650 __tmp.put_u8(self.heading);
28651 __tmp.put_u8(self.target_heading);
28652 __tmp.put_u8(self.throttle);
28653 __tmp.put_u8(self.airspeed);
28654 __tmp.put_u8(self.airspeed_sp);
28655 __tmp.put_u8(self.groundspeed);
28656 __tmp.put_u8(self.windspeed);
28657 __tmp.put_u8(self.wind_heading);
28658 __tmp.put_u8(self.eph);
28659 __tmp.put_u8(self.epv);
28660 __tmp.put_i8(self.temperature_air);
28661 __tmp.put_i8(self.climb_rate);
28662 __tmp.put_i8(self.battery);
28663 __tmp.put_i8(self.custom0);
28664 __tmp.put_i8(self.custom1);
28665 __tmp.put_i8(self.custom2);
28666 if matches!(version, MavlinkVersion::V2) {
28667 let len = __tmp.len();
28668 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28669 } else {
28670 __tmp.len()
28671 }
28672 }
28673}
28674#[doc = "id: 105"]
28675#[doc = "The IMU readings in SI units in NED body frame."]
28676#[derive(Debug, Clone, PartialEq)]
28677#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28678#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28679pub struct HIGHRES_IMU_DATA {
28680 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
28681 pub time_usec: u64,
28682 #[doc = "X acceleration"]
28683 pub xacc: f32,
28684 #[doc = "Y acceleration"]
28685 pub yacc: f32,
28686 #[doc = "Z acceleration"]
28687 pub zacc: f32,
28688 #[doc = "Angular speed around X axis"]
28689 pub xgyro: f32,
28690 #[doc = "Angular speed around Y axis"]
28691 pub ygyro: f32,
28692 #[doc = "Angular speed around Z axis"]
28693 pub zgyro: f32,
28694 #[doc = "X Magnetic field"]
28695 pub xmag: f32,
28696 #[doc = "Y Magnetic field"]
28697 pub ymag: f32,
28698 #[doc = "Z Magnetic field"]
28699 pub zmag: f32,
28700 #[doc = "Absolute pressure"]
28701 pub abs_pressure: f32,
28702 #[doc = "Differential pressure"]
28703 pub diff_pressure: f32,
28704 #[doc = "Altitude calculated from pressure"]
28705 pub pressure_alt: f32,
28706 #[doc = "Temperature"]
28707 pub temperature: f32,
28708 #[doc = "Bitmap for fields that have updated since last message"]
28709 pub fields_updated: HighresImuUpdatedFlags,
28710 #[doc = "Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)"]
28711 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
28712 pub id: u8,
28713}
28714impl HIGHRES_IMU_DATA {
28715 pub const ENCODED_LEN: usize = 63usize;
28716 pub const DEFAULT: Self = Self {
28717 time_usec: 0_u64,
28718 xacc: 0.0_f32,
28719 yacc: 0.0_f32,
28720 zacc: 0.0_f32,
28721 xgyro: 0.0_f32,
28722 ygyro: 0.0_f32,
28723 zgyro: 0.0_f32,
28724 xmag: 0.0_f32,
28725 ymag: 0.0_f32,
28726 zmag: 0.0_f32,
28727 abs_pressure: 0.0_f32,
28728 diff_pressure: 0.0_f32,
28729 pressure_alt: 0.0_f32,
28730 temperature: 0.0_f32,
28731 fields_updated: HighresImuUpdatedFlags::DEFAULT,
28732 id: 0_u8,
28733 };
28734 #[cfg(feature = "arbitrary")]
28735 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28736 use arbitrary::{Arbitrary, Unstructured};
28737 let mut buf = [0u8; 1024];
28738 rng.fill_bytes(&mut buf);
28739 let mut unstructured = Unstructured::new(&buf);
28740 Self::arbitrary(&mut unstructured).unwrap_or_default()
28741 }
28742}
28743impl Default for HIGHRES_IMU_DATA {
28744 fn default() -> Self {
28745 Self::DEFAULT.clone()
28746 }
28747}
28748impl MessageData for HIGHRES_IMU_DATA {
28749 type Message = MavMessage;
28750 const ID: u32 = 105u32;
28751 const NAME: &'static str = "HIGHRES_IMU";
28752 const EXTRA_CRC: u8 = 93u8;
28753 const ENCODED_LEN: usize = 63usize;
28754 fn deser(
28755 _version: MavlinkVersion,
28756 __input: &[u8],
28757 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28758 let avail_len = __input.len();
28759 let mut payload_buf = [0; Self::ENCODED_LEN];
28760 let mut buf = if avail_len < Self::ENCODED_LEN {
28761 payload_buf[0..avail_len].copy_from_slice(__input);
28762 Bytes::new(&payload_buf)
28763 } else {
28764 Bytes::new(__input)
28765 };
28766 let mut __struct = Self::default();
28767 __struct.time_usec = buf.get_u64_le();
28768 __struct.xacc = buf.get_f32_le();
28769 __struct.yacc = buf.get_f32_le();
28770 __struct.zacc = buf.get_f32_le();
28771 __struct.xgyro = buf.get_f32_le();
28772 __struct.ygyro = buf.get_f32_le();
28773 __struct.zgyro = buf.get_f32_le();
28774 __struct.xmag = buf.get_f32_le();
28775 __struct.ymag = buf.get_f32_le();
28776 __struct.zmag = buf.get_f32_le();
28777 __struct.abs_pressure = buf.get_f32_le();
28778 __struct.diff_pressure = buf.get_f32_le();
28779 __struct.pressure_alt = buf.get_f32_le();
28780 __struct.temperature = buf.get_f32_le();
28781 let tmp = buf.get_u16_le();
28782 __struct.fields_updated = HighresImuUpdatedFlags::from_bits(
28783 tmp & HighresImuUpdatedFlags::all().bits(),
28784 )
28785 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
28786 flag_type: "HighresImuUpdatedFlags",
28787 value: tmp as u32,
28788 })?;
28789 __struct.id = buf.get_u8();
28790 Ok(__struct)
28791 }
28792 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28793 let mut __tmp = BytesMut::new(bytes);
28794 #[allow(clippy::absurd_extreme_comparisons)]
28795 #[allow(unused_comparisons)]
28796 if __tmp.remaining() < Self::ENCODED_LEN {
28797 panic!(
28798 "buffer is too small (need {} bytes, but got {})",
28799 Self::ENCODED_LEN,
28800 __tmp.remaining(),
28801 )
28802 }
28803 __tmp.put_u64_le(self.time_usec);
28804 __tmp.put_f32_le(self.xacc);
28805 __tmp.put_f32_le(self.yacc);
28806 __tmp.put_f32_le(self.zacc);
28807 __tmp.put_f32_le(self.xgyro);
28808 __tmp.put_f32_le(self.ygyro);
28809 __tmp.put_f32_le(self.zgyro);
28810 __tmp.put_f32_le(self.xmag);
28811 __tmp.put_f32_le(self.ymag);
28812 __tmp.put_f32_le(self.zmag);
28813 __tmp.put_f32_le(self.abs_pressure);
28814 __tmp.put_f32_le(self.diff_pressure);
28815 __tmp.put_f32_le(self.pressure_alt);
28816 __tmp.put_f32_le(self.temperature);
28817 __tmp.put_u16_le(self.fields_updated.bits());
28818 __tmp.put_u8(self.id);
28819 if matches!(version, MavlinkVersion::V2) {
28820 let len = __tmp.len();
28821 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28822 } else {
28823 __tmp.len()
28824 }
28825 }
28826}
28827#[doc = "id: 91"]
28828#[doc = "Sent from autopilot to simulation. Hardware in the loop control outputs. Alternative to HIL_ACTUATOR_CONTROLS."]
28829#[derive(Debug, Clone, PartialEq)]
28830#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28831#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28832pub struct HIL_CONTROLS_DATA {
28833 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
28834 pub time_usec: u64,
28835 #[doc = "Control output -1 .. 1"]
28836 pub roll_ailerons: f32,
28837 #[doc = "Control output -1 .. 1"]
28838 pub pitch_elevator: f32,
28839 #[doc = "Control output -1 .. 1"]
28840 pub yaw_rudder: f32,
28841 #[doc = "Throttle 0 .. 1"]
28842 pub throttle: f32,
28843 #[doc = "Aux 1, -1 .. 1"]
28844 pub aux1: f32,
28845 #[doc = "Aux 2, -1 .. 1"]
28846 pub aux2: f32,
28847 #[doc = "Aux 3, -1 .. 1"]
28848 pub aux3: f32,
28849 #[doc = "Aux 4, -1 .. 1"]
28850 pub aux4: f32,
28851 #[doc = "System mode."]
28852 pub mode: MavMode,
28853 #[doc = "Navigation mode (MAV_NAV_MODE)"]
28854 pub nav_mode: u8,
28855}
28856impl HIL_CONTROLS_DATA {
28857 pub const ENCODED_LEN: usize = 42usize;
28858 pub const DEFAULT: Self = Self {
28859 time_usec: 0_u64,
28860 roll_ailerons: 0.0_f32,
28861 pitch_elevator: 0.0_f32,
28862 yaw_rudder: 0.0_f32,
28863 throttle: 0.0_f32,
28864 aux1: 0.0_f32,
28865 aux2: 0.0_f32,
28866 aux3: 0.0_f32,
28867 aux4: 0.0_f32,
28868 mode: MavMode::DEFAULT,
28869 nav_mode: 0_u8,
28870 };
28871 #[cfg(feature = "arbitrary")]
28872 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28873 use arbitrary::{Arbitrary, Unstructured};
28874 let mut buf = [0u8; 1024];
28875 rng.fill_bytes(&mut buf);
28876 let mut unstructured = Unstructured::new(&buf);
28877 Self::arbitrary(&mut unstructured).unwrap_or_default()
28878 }
28879}
28880impl Default for HIL_CONTROLS_DATA {
28881 fn default() -> Self {
28882 Self::DEFAULT.clone()
28883 }
28884}
28885impl MessageData for HIL_CONTROLS_DATA {
28886 type Message = MavMessage;
28887 const ID: u32 = 91u32;
28888 const NAME: &'static str = "HIL_CONTROLS";
28889 const EXTRA_CRC: u8 = 63u8;
28890 const ENCODED_LEN: usize = 42usize;
28891 fn deser(
28892 _version: MavlinkVersion,
28893 __input: &[u8],
28894 ) -> Result<Self, ::mavlink_core::error::ParserError> {
28895 let avail_len = __input.len();
28896 let mut payload_buf = [0; Self::ENCODED_LEN];
28897 let mut buf = if avail_len < Self::ENCODED_LEN {
28898 payload_buf[0..avail_len].copy_from_slice(__input);
28899 Bytes::new(&payload_buf)
28900 } else {
28901 Bytes::new(__input)
28902 };
28903 let mut __struct = Self::default();
28904 __struct.time_usec = buf.get_u64_le();
28905 __struct.roll_ailerons = buf.get_f32_le();
28906 __struct.pitch_elevator = buf.get_f32_le();
28907 __struct.yaw_rudder = buf.get_f32_le();
28908 __struct.throttle = buf.get_f32_le();
28909 __struct.aux1 = buf.get_f32_le();
28910 __struct.aux2 = buf.get_f32_le();
28911 __struct.aux3 = buf.get_f32_le();
28912 __struct.aux4 = buf.get_f32_le();
28913 let tmp = buf.get_u8();
28914 __struct.mode =
28915 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
28916 enum_type: "MavMode",
28917 value: tmp as u32,
28918 })?;
28919 __struct.nav_mode = buf.get_u8();
28920 Ok(__struct)
28921 }
28922 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
28923 let mut __tmp = BytesMut::new(bytes);
28924 #[allow(clippy::absurd_extreme_comparisons)]
28925 #[allow(unused_comparisons)]
28926 if __tmp.remaining() < Self::ENCODED_LEN {
28927 panic!(
28928 "buffer is too small (need {} bytes, but got {})",
28929 Self::ENCODED_LEN,
28930 __tmp.remaining(),
28931 )
28932 }
28933 __tmp.put_u64_le(self.time_usec);
28934 __tmp.put_f32_le(self.roll_ailerons);
28935 __tmp.put_f32_le(self.pitch_elevator);
28936 __tmp.put_f32_le(self.yaw_rudder);
28937 __tmp.put_f32_le(self.throttle);
28938 __tmp.put_f32_le(self.aux1);
28939 __tmp.put_f32_le(self.aux2);
28940 __tmp.put_f32_le(self.aux3);
28941 __tmp.put_f32_le(self.aux4);
28942 __tmp.put_u8(self.mode as u8);
28943 __tmp.put_u8(self.nav_mode);
28944 if matches!(version, MavlinkVersion::V2) {
28945 let len = __tmp.len();
28946 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
28947 } else {
28948 __tmp.len()
28949 }
28950 }
28951}
28952#[doc = "id: 40"]
28953#[doc = "Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. <https://mavlink.io/en/services/mission.html>."]
28954#[derive(Debug, Clone, PartialEq)]
28955#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
28956#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
28957pub struct MISSION_REQUEST_DATA {
28958 #[doc = "Sequence"]
28959 pub seq: u16,
28960 #[doc = "System ID"]
28961 pub target_system: u8,
28962 #[doc = "Component ID"]
28963 pub target_component: u8,
28964 #[doc = "Mission type."]
28965 #[cfg_attr(feature = "serde", serde(default))]
28966 pub mission_type: MavMissionType,
28967}
28968impl MISSION_REQUEST_DATA {
28969 pub const ENCODED_LEN: usize = 5usize;
28970 pub const DEFAULT: Self = Self {
28971 seq: 0_u16,
28972 target_system: 0_u8,
28973 target_component: 0_u8,
28974 mission_type: MavMissionType::DEFAULT,
28975 };
28976 #[cfg(feature = "arbitrary")]
28977 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
28978 use arbitrary::{Arbitrary, Unstructured};
28979 let mut buf = [0u8; 1024];
28980 rng.fill_bytes(&mut buf);
28981 let mut unstructured = Unstructured::new(&buf);
28982 Self::arbitrary(&mut unstructured).unwrap_or_default()
28983 }
28984}
28985impl Default for MISSION_REQUEST_DATA {
28986 fn default() -> Self {
28987 Self::DEFAULT.clone()
28988 }
28989}
28990impl MessageData for MISSION_REQUEST_DATA {
28991 type Message = MavMessage;
28992 const ID: u32 = 40u32;
28993 const NAME: &'static str = "MISSION_REQUEST";
28994 const EXTRA_CRC: u8 = 230u8;
28995 const ENCODED_LEN: usize = 5usize;
28996 fn deser(
28997 _version: MavlinkVersion,
28998 __input: &[u8],
28999 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29000 let avail_len = __input.len();
29001 let mut payload_buf = [0; Self::ENCODED_LEN];
29002 let mut buf = if avail_len < Self::ENCODED_LEN {
29003 payload_buf[0..avail_len].copy_from_slice(__input);
29004 Bytes::new(&payload_buf)
29005 } else {
29006 Bytes::new(__input)
29007 };
29008 let mut __struct = Self::default();
29009 __struct.seq = buf.get_u16_le();
29010 __struct.target_system = buf.get_u8();
29011 __struct.target_component = buf.get_u8();
29012 let tmp = buf.get_u8();
29013 __struct.mission_type =
29014 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29015 enum_type: "MavMissionType",
29016 value: tmp as u32,
29017 })?;
29018 Ok(__struct)
29019 }
29020 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29021 let mut __tmp = BytesMut::new(bytes);
29022 #[allow(clippy::absurd_extreme_comparisons)]
29023 #[allow(unused_comparisons)]
29024 if __tmp.remaining() < Self::ENCODED_LEN {
29025 panic!(
29026 "buffer is too small (need {} bytes, but got {})",
29027 Self::ENCODED_LEN,
29028 __tmp.remaining(),
29029 )
29030 }
29031 __tmp.put_u16_le(self.seq);
29032 __tmp.put_u8(self.target_system);
29033 __tmp.put_u8(self.target_component);
29034 __tmp.put_u8(self.mission_type as u8);
29035 if matches!(version, MavlinkVersion::V2) {
29036 let len = __tmp.len();
29037 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29038 } else {
29039 __tmp.len()
29040 }
29041 }
29042}
29043#[doc = "id: 149"]
29044#[doc = "The location of a landing target. See: <https://mavlink.io/en/services/landing_target.html>."]
29045#[derive(Debug, Clone, PartialEq)]
29046#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29047#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29048pub struct LANDING_TARGET_DATA {
29049 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
29050 pub time_usec: u64,
29051 #[doc = "X-axis angular offset of the target from the center of the image"]
29052 pub angle_x: f32,
29053 #[doc = "Y-axis angular offset of the target from the center of the image"]
29054 pub angle_y: f32,
29055 #[doc = "Distance to the target from the vehicle"]
29056 pub distance: f32,
29057 #[doc = "Size of target along x-axis"]
29058 pub size_x: f32,
29059 #[doc = "Size of target along y-axis"]
29060 pub size_y: f32,
29061 #[doc = "The ID of the target if multiple targets are present"]
29062 pub target_num: u8,
29063 #[doc = "Coordinate frame used for following fields."]
29064 pub frame: MavFrame,
29065 #[doc = "X Position of the landing target in MAV_FRAME"]
29066 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29067 pub x: f32,
29068 #[doc = "Y Position of the landing target in MAV_FRAME"]
29069 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29070 pub y: f32,
29071 #[doc = "Z Position of the landing target in MAV_FRAME"]
29072 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29073 pub z: f32,
29074 #[doc = "Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
29075 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29076 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29077 pub q: [f32; 4],
29078 #[doc = "Type of landing target"]
29079 #[cfg_attr(feature = "serde", serde(default))]
29080 pub mavtype: LandingTargetType,
29081 #[doc = "Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid)."]
29082 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29083 pub position_valid: u8,
29084}
29085impl LANDING_TARGET_DATA {
29086 pub const ENCODED_LEN: usize = 60usize;
29087 pub const DEFAULT: Self = Self {
29088 time_usec: 0_u64,
29089 angle_x: 0.0_f32,
29090 angle_y: 0.0_f32,
29091 distance: 0.0_f32,
29092 size_x: 0.0_f32,
29093 size_y: 0.0_f32,
29094 target_num: 0_u8,
29095 frame: MavFrame::DEFAULT,
29096 x: 0.0_f32,
29097 y: 0.0_f32,
29098 z: 0.0_f32,
29099 q: [0.0_f32; 4usize],
29100 mavtype: LandingTargetType::DEFAULT,
29101 position_valid: 0_u8,
29102 };
29103 #[cfg(feature = "arbitrary")]
29104 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29105 use arbitrary::{Arbitrary, Unstructured};
29106 let mut buf = [0u8; 1024];
29107 rng.fill_bytes(&mut buf);
29108 let mut unstructured = Unstructured::new(&buf);
29109 Self::arbitrary(&mut unstructured).unwrap_or_default()
29110 }
29111}
29112impl Default for LANDING_TARGET_DATA {
29113 fn default() -> Self {
29114 Self::DEFAULT.clone()
29115 }
29116}
29117impl MessageData for LANDING_TARGET_DATA {
29118 type Message = MavMessage;
29119 const ID: u32 = 149u32;
29120 const NAME: &'static str = "LANDING_TARGET";
29121 const EXTRA_CRC: u8 = 200u8;
29122 const ENCODED_LEN: usize = 60usize;
29123 fn deser(
29124 _version: MavlinkVersion,
29125 __input: &[u8],
29126 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29127 let avail_len = __input.len();
29128 let mut payload_buf = [0; Self::ENCODED_LEN];
29129 let mut buf = if avail_len < Self::ENCODED_LEN {
29130 payload_buf[0..avail_len].copy_from_slice(__input);
29131 Bytes::new(&payload_buf)
29132 } else {
29133 Bytes::new(__input)
29134 };
29135 let mut __struct = Self::default();
29136 __struct.time_usec = buf.get_u64_le();
29137 __struct.angle_x = buf.get_f32_le();
29138 __struct.angle_y = buf.get_f32_le();
29139 __struct.distance = buf.get_f32_le();
29140 __struct.size_x = buf.get_f32_le();
29141 __struct.size_y = buf.get_f32_le();
29142 __struct.target_num = buf.get_u8();
29143 let tmp = buf.get_u8();
29144 __struct.frame =
29145 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29146 enum_type: "MavFrame",
29147 value: tmp as u32,
29148 })?;
29149 __struct.x = buf.get_f32_le();
29150 __struct.y = buf.get_f32_le();
29151 __struct.z = buf.get_f32_le();
29152 for v in &mut __struct.q {
29153 let val = buf.get_f32_le();
29154 *v = val;
29155 }
29156 let tmp = buf.get_u8();
29157 __struct.mavtype =
29158 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29159 enum_type: "LandingTargetType",
29160 value: tmp as u32,
29161 })?;
29162 __struct.position_valid = buf.get_u8();
29163 Ok(__struct)
29164 }
29165 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29166 let mut __tmp = BytesMut::new(bytes);
29167 #[allow(clippy::absurd_extreme_comparisons)]
29168 #[allow(unused_comparisons)]
29169 if __tmp.remaining() < Self::ENCODED_LEN {
29170 panic!(
29171 "buffer is too small (need {} bytes, but got {})",
29172 Self::ENCODED_LEN,
29173 __tmp.remaining(),
29174 )
29175 }
29176 __tmp.put_u64_le(self.time_usec);
29177 __tmp.put_f32_le(self.angle_x);
29178 __tmp.put_f32_le(self.angle_y);
29179 __tmp.put_f32_le(self.distance);
29180 __tmp.put_f32_le(self.size_x);
29181 __tmp.put_f32_le(self.size_y);
29182 __tmp.put_u8(self.target_num);
29183 __tmp.put_u8(self.frame as u8);
29184 __tmp.put_f32_le(self.x);
29185 __tmp.put_f32_le(self.y);
29186 __tmp.put_f32_le(self.z);
29187 for val in &self.q {
29188 __tmp.put_f32_le(*val);
29189 }
29190 __tmp.put_u8(self.mavtype as u8);
29191 __tmp.put_u8(self.position_valid);
29192 if matches!(version, MavlinkVersion::V2) {
29193 let len = __tmp.len();
29194 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29195 } else {
29196 __tmp.len()
29197 }
29198 }
29199}
29200#[doc = "id: 117"]
29201#[doc = "Request a list of available logs. On some systems calling this may stop on-board logging until LOG_REQUEST_END is called. If there are no log files available this request shall be answered with one LOG_ENTRY message with id = 0 and num_logs = 0."]
29202#[derive(Debug, Clone, PartialEq)]
29203#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29204#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29205pub struct LOG_REQUEST_LIST_DATA {
29206 #[doc = "First log id (0 for first available)"]
29207 pub start: u16,
29208 #[doc = "Last log id (0xffff for last available)"]
29209 pub end: u16,
29210 #[doc = "System ID"]
29211 pub target_system: u8,
29212 #[doc = "Component ID"]
29213 pub target_component: u8,
29214}
29215impl LOG_REQUEST_LIST_DATA {
29216 pub const ENCODED_LEN: usize = 6usize;
29217 pub const DEFAULT: Self = Self {
29218 start: 0_u16,
29219 end: 0_u16,
29220 target_system: 0_u8,
29221 target_component: 0_u8,
29222 };
29223 #[cfg(feature = "arbitrary")]
29224 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29225 use arbitrary::{Arbitrary, Unstructured};
29226 let mut buf = [0u8; 1024];
29227 rng.fill_bytes(&mut buf);
29228 let mut unstructured = Unstructured::new(&buf);
29229 Self::arbitrary(&mut unstructured).unwrap_or_default()
29230 }
29231}
29232impl Default for LOG_REQUEST_LIST_DATA {
29233 fn default() -> Self {
29234 Self::DEFAULT.clone()
29235 }
29236}
29237impl MessageData for LOG_REQUEST_LIST_DATA {
29238 type Message = MavMessage;
29239 const ID: u32 = 117u32;
29240 const NAME: &'static str = "LOG_REQUEST_LIST";
29241 const EXTRA_CRC: u8 = 128u8;
29242 const ENCODED_LEN: usize = 6usize;
29243 fn deser(
29244 _version: MavlinkVersion,
29245 __input: &[u8],
29246 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29247 let avail_len = __input.len();
29248 let mut payload_buf = [0; Self::ENCODED_LEN];
29249 let mut buf = if avail_len < Self::ENCODED_LEN {
29250 payload_buf[0..avail_len].copy_from_slice(__input);
29251 Bytes::new(&payload_buf)
29252 } else {
29253 Bytes::new(__input)
29254 };
29255 let mut __struct = Self::default();
29256 __struct.start = buf.get_u16_le();
29257 __struct.end = buf.get_u16_le();
29258 __struct.target_system = buf.get_u8();
29259 __struct.target_component = buf.get_u8();
29260 Ok(__struct)
29261 }
29262 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29263 let mut __tmp = BytesMut::new(bytes);
29264 #[allow(clippy::absurd_extreme_comparisons)]
29265 #[allow(unused_comparisons)]
29266 if __tmp.remaining() < Self::ENCODED_LEN {
29267 panic!(
29268 "buffer is too small (need {} bytes, but got {})",
29269 Self::ENCODED_LEN,
29270 __tmp.remaining(),
29271 )
29272 }
29273 __tmp.put_u16_le(self.start);
29274 __tmp.put_u16_le(self.end);
29275 __tmp.put_u8(self.target_system);
29276 __tmp.put_u8(self.target_component);
29277 if matches!(version, MavlinkVersion::V2) {
29278 let len = __tmp.len();
29279 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29280 } else {
29281 __tmp.len()
29282 }
29283 }
29284}
29285#[doc = "id: 271"]
29286#[doc = "Information about the field of view of a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
29287#[derive(Debug, Clone, PartialEq)]
29288#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29289#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29290pub struct CAMERA_FOV_STATUS_DATA {
29291 #[doc = "Timestamp (time since system boot)."]
29292 pub time_boot_ms: u32,
29293 #[doc = "Latitude of camera (INT32_MAX if unknown)."]
29294 pub lat_camera: i32,
29295 #[doc = "Longitude of camera (INT32_MAX if unknown)."]
29296 pub lon_camera: i32,
29297 #[doc = "Altitude (MSL) of camera (INT32_MAX if unknown)."]
29298 pub alt_camera: i32,
29299 #[doc = "Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
29300 pub lat_image: i32,
29301 #[doc = "Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
29302 pub lon_image: i32,
29303 #[doc = "Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon)."]
29304 pub alt_image: i32,
29305 #[doc = "Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)"]
29306 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29307 pub q: [f32; 4],
29308 #[doc = "Horizontal field of view (NaN if unknown)."]
29309 pub hfov: f32,
29310 #[doc = "Vertical field of view (NaN if unknown)."]
29311 pub vfov: f32,
29312 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
29313 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29314 pub camera_device_id: u8,
29315}
29316impl CAMERA_FOV_STATUS_DATA {
29317 pub const ENCODED_LEN: usize = 53usize;
29318 pub const DEFAULT: Self = Self {
29319 time_boot_ms: 0_u32,
29320 lat_camera: 0_i32,
29321 lon_camera: 0_i32,
29322 alt_camera: 0_i32,
29323 lat_image: 0_i32,
29324 lon_image: 0_i32,
29325 alt_image: 0_i32,
29326 q: [0.0_f32; 4usize],
29327 hfov: 0.0_f32,
29328 vfov: 0.0_f32,
29329 camera_device_id: 0_u8,
29330 };
29331 #[cfg(feature = "arbitrary")]
29332 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29333 use arbitrary::{Arbitrary, Unstructured};
29334 let mut buf = [0u8; 1024];
29335 rng.fill_bytes(&mut buf);
29336 let mut unstructured = Unstructured::new(&buf);
29337 Self::arbitrary(&mut unstructured).unwrap_or_default()
29338 }
29339}
29340impl Default for CAMERA_FOV_STATUS_DATA {
29341 fn default() -> Self {
29342 Self::DEFAULT.clone()
29343 }
29344}
29345impl MessageData for CAMERA_FOV_STATUS_DATA {
29346 type Message = MavMessage;
29347 const ID: u32 = 271u32;
29348 const NAME: &'static str = "CAMERA_FOV_STATUS";
29349 const EXTRA_CRC: u8 = 22u8;
29350 const ENCODED_LEN: usize = 53usize;
29351 fn deser(
29352 _version: MavlinkVersion,
29353 __input: &[u8],
29354 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29355 let avail_len = __input.len();
29356 let mut payload_buf = [0; Self::ENCODED_LEN];
29357 let mut buf = if avail_len < Self::ENCODED_LEN {
29358 payload_buf[0..avail_len].copy_from_slice(__input);
29359 Bytes::new(&payload_buf)
29360 } else {
29361 Bytes::new(__input)
29362 };
29363 let mut __struct = Self::default();
29364 __struct.time_boot_ms = buf.get_u32_le();
29365 __struct.lat_camera = buf.get_i32_le();
29366 __struct.lon_camera = buf.get_i32_le();
29367 __struct.alt_camera = buf.get_i32_le();
29368 __struct.lat_image = buf.get_i32_le();
29369 __struct.lon_image = buf.get_i32_le();
29370 __struct.alt_image = buf.get_i32_le();
29371 for v in &mut __struct.q {
29372 let val = buf.get_f32_le();
29373 *v = val;
29374 }
29375 __struct.hfov = buf.get_f32_le();
29376 __struct.vfov = buf.get_f32_le();
29377 __struct.camera_device_id = buf.get_u8();
29378 Ok(__struct)
29379 }
29380 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29381 let mut __tmp = BytesMut::new(bytes);
29382 #[allow(clippy::absurd_extreme_comparisons)]
29383 #[allow(unused_comparisons)]
29384 if __tmp.remaining() < Self::ENCODED_LEN {
29385 panic!(
29386 "buffer is too small (need {} bytes, but got {})",
29387 Self::ENCODED_LEN,
29388 __tmp.remaining(),
29389 )
29390 }
29391 __tmp.put_u32_le(self.time_boot_ms);
29392 __tmp.put_i32_le(self.lat_camera);
29393 __tmp.put_i32_le(self.lon_camera);
29394 __tmp.put_i32_le(self.alt_camera);
29395 __tmp.put_i32_le(self.lat_image);
29396 __tmp.put_i32_le(self.lon_image);
29397 __tmp.put_i32_le(self.alt_image);
29398 for val in &self.q {
29399 __tmp.put_f32_le(*val);
29400 }
29401 __tmp.put_f32_le(self.hfov);
29402 __tmp.put_f32_le(self.vfov);
29403 __tmp.put_u8(self.camera_device_id);
29404 if matches!(version, MavlinkVersion::V2) {
29405 let len = __tmp.len();
29406 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29407 } else {
29408 __tmp.len()
29409 }
29410 }
29411}
29412#[doc = "id: 118"]
29413#[doc = "Reply to LOG_REQUEST_LIST."]
29414#[derive(Debug, Clone, PartialEq)]
29415#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29416#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29417pub struct LOG_ENTRY_DATA {
29418 #[doc = "UTC timestamp of log since 1970, or 0 if not available"]
29419 pub time_utc: u32,
29420 #[doc = "Size of the log (may be approximate)"]
29421 pub size: u32,
29422 #[doc = "Log id"]
29423 pub id: u16,
29424 #[doc = "Total number of logs"]
29425 pub num_logs: u16,
29426 #[doc = "High log number"]
29427 pub last_log_num: u16,
29428}
29429impl LOG_ENTRY_DATA {
29430 pub const ENCODED_LEN: usize = 14usize;
29431 pub const DEFAULT: Self = Self {
29432 time_utc: 0_u32,
29433 size: 0_u32,
29434 id: 0_u16,
29435 num_logs: 0_u16,
29436 last_log_num: 0_u16,
29437 };
29438 #[cfg(feature = "arbitrary")]
29439 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29440 use arbitrary::{Arbitrary, Unstructured};
29441 let mut buf = [0u8; 1024];
29442 rng.fill_bytes(&mut buf);
29443 let mut unstructured = Unstructured::new(&buf);
29444 Self::arbitrary(&mut unstructured).unwrap_or_default()
29445 }
29446}
29447impl Default for LOG_ENTRY_DATA {
29448 fn default() -> Self {
29449 Self::DEFAULT.clone()
29450 }
29451}
29452impl MessageData for LOG_ENTRY_DATA {
29453 type Message = MavMessage;
29454 const ID: u32 = 118u32;
29455 const NAME: &'static str = "LOG_ENTRY";
29456 const EXTRA_CRC: u8 = 56u8;
29457 const ENCODED_LEN: usize = 14usize;
29458 fn deser(
29459 _version: MavlinkVersion,
29460 __input: &[u8],
29461 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29462 let avail_len = __input.len();
29463 let mut payload_buf = [0; Self::ENCODED_LEN];
29464 let mut buf = if avail_len < Self::ENCODED_LEN {
29465 payload_buf[0..avail_len].copy_from_slice(__input);
29466 Bytes::new(&payload_buf)
29467 } else {
29468 Bytes::new(__input)
29469 };
29470 let mut __struct = Self::default();
29471 __struct.time_utc = buf.get_u32_le();
29472 __struct.size = buf.get_u32_le();
29473 __struct.id = buf.get_u16_le();
29474 __struct.num_logs = buf.get_u16_le();
29475 __struct.last_log_num = buf.get_u16_le();
29476 Ok(__struct)
29477 }
29478 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29479 let mut __tmp = BytesMut::new(bytes);
29480 #[allow(clippy::absurd_extreme_comparisons)]
29481 #[allow(unused_comparisons)]
29482 if __tmp.remaining() < Self::ENCODED_LEN {
29483 panic!(
29484 "buffer is too small (need {} bytes, but got {})",
29485 Self::ENCODED_LEN,
29486 __tmp.remaining(),
29487 )
29488 }
29489 __tmp.put_u32_le(self.time_utc);
29490 __tmp.put_u32_le(self.size);
29491 __tmp.put_u16_le(self.id);
29492 __tmp.put_u16_le(self.num_logs);
29493 __tmp.put_u16_le(self.last_log_num);
29494 if matches!(version, MavlinkVersion::V2) {
29495 let len = __tmp.len();
29496 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29497 } else {
29498 __tmp.len()
29499 }
29500 }
29501}
29502#[doc = "id: 123"]
29503#[doc = "Data for injecting into the onboard GPS (used for DGPS)."]
29504#[derive(Debug, Clone, PartialEq)]
29505#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29506#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29507pub struct GPS_INJECT_DATA_DATA {
29508 #[doc = "System ID"]
29509 pub target_system: u8,
29510 #[doc = "Component ID"]
29511 pub target_component: u8,
29512 #[doc = "Data length"]
29513 pub len: u8,
29514 #[doc = "Raw data (110 is enough for 12 satellites of RTCMv2)"]
29515 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29516 pub data: [u8; 110],
29517}
29518impl GPS_INJECT_DATA_DATA {
29519 pub const ENCODED_LEN: usize = 113usize;
29520 pub const DEFAULT: Self = Self {
29521 target_system: 0_u8,
29522 target_component: 0_u8,
29523 len: 0_u8,
29524 data: [0_u8; 110usize],
29525 };
29526 #[cfg(feature = "arbitrary")]
29527 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29528 use arbitrary::{Arbitrary, Unstructured};
29529 let mut buf = [0u8; 1024];
29530 rng.fill_bytes(&mut buf);
29531 let mut unstructured = Unstructured::new(&buf);
29532 Self::arbitrary(&mut unstructured).unwrap_or_default()
29533 }
29534}
29535impl Default for GPS_INJECT_DATA_DATA {
29536 fn default() -> Self {
29537 Self::DEFAULT.clone()
29538 }
29539}
29540impl MessageData for GPS_INJECT_DATA_DATA {
29541 type Message = MavMessage;
29542 const ID: u32 = 123u32;
29543 const NAME: &'static str = "GPS_INJECT_DATA";
29544 const EXTRA_CRC: u8 = 250u8;
29545 const ENCODED_LEN: usize = 113usize;
29546 fn deser(
29547 _version: MavlinkVersion,
29548 __input: &[u8],
29549 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29550 let avail_len = __input.len();
29551 let mut payload_buf = [0; Self::ENCODED_LEN];
29552 let mut buf = if avail_len < Self::ENCODED_LEN {
29553 payload_buf[0..avail_len].copy_from_slice(__input);
29554 Bytes::new(&payload_buf)
29555 } else {
29556 Bytes::new(__input)
29557 };
29558 let mut __struct = Self::default();
29559 __struct.target_system = buf.get_u8();
29560 __struct.target_component = buf.get_u8();
29561 __struct.len = buf.get_u8();
29562 for v in &mut __struct.data {
29563 let val = buf.get_u8();
29564 *v = val;
29565 }
29566 Ok(__struct)
29567 }
29568 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29569 let mut __tmp = BytesMut::new(bytes);
29570 #[allow(clippy::absurd_extreme_comparisons)]
29571 #[allow(unused_comparisons)]
29572 if __tmp.remaining() < Self::ENCODED_LEN {
29573 panic!(
29574 "buffer is too small (need {} bytes, but got {})",
29575 Self::ENCODED_LEN,
29576 __tmp.remaining(),
29577 )
29578 }
29579 __tmp.put_u8(self.target_system);
29580 __tmp.put_u8(self.target_component);
29581 __tmp.put_u8(self.len);
29582 for val in &self.data {
29583 __tmp.put_u8(*val);
29584 }
29585 if matches!(version, MavlinkVersion::V2) {
29586 let len = __tmp.len();
29587 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29588 } else {
29589 __tmp.len()
29590 }
29591 }
29592}
29593#[doc = "id: 22"]
29594#[doc = "Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout. The parameter microservice is documented at <https://mavlink.io/en/services/parameter.html>."]
29595#[derive(Debug, Clone, PartialEq)]
29596#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29597#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29598pub struct PARAM_VALUE_DATA {
29599 #[doc = "Onboard parameter value"]
29600 pub param_value: f32,
29601 #[doc = "Total number of onboard parameters"]
29602 pub param_count: u16,
29603 #[doc = "Index of this onboard parameter"]
29604 pub param_index: u16,
29605 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
29606 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29607 pub param_id: [u8; 16],
29608 #[doc = "Onboard parameter type."]
29609 pub param_type: MavParamType,
29610}
29611impl PARAM_VALUE_DATA {
29612 pub const ENCODED_LEN: usize = 25usize;
29613 pub const DEFAULT: Self = Self {
29614 param_value: 0.0_f32,
29615 param_count: 0_u16,
29616 param_index: 0_u16,
29617 param_id: [0_u8; 16usize],
29618 param_type: MavParamType::DEFAULT,
29619 };
29620 #[cfg(feature = "arbitrary")]
29621 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29622 use arbitrary::{Arbitrary, Unstructured};
29623 let mut buf = [0u8; 1024];
29624 rng.fill_bytes(&mut buf);
29625 let mut unstructured = Unstructured::new(&buf);
29626 Self::arbitrary(&mut unstructured).unwrap_or_default()
29627 }
29628}
29629impl Default for PARAM_VALUE_DATA {
29630 fn default() -> Self {
29631 Self::DEFAULT.clone()
29632 }
29633}
29634impl MessageData for PARAM_VALUE_DATA {
29635 type Message = MavMessage;
29636 const ID: u32 = 22u32;
29637 const NAME: &'static str = "PARAM_VALUE";
29638 const EXTRA_CRC: u8 = 220u8;
29639 const ENCODED_LEN: usize = 25usize;
29640 fn deser(
29641 _version: MavlinkVersion,
29642 __input: &[u8],
29643 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29644 let avail_len = __input.len();
29645 let mut payload_buf = [0; Self::ENCODED_LEN];
29646 let mut buf = if avail_len < Self::ENCODED_LEN {
29647 payload_buf[0..avail_len].copy_from_slice(__input);
29648 Bytes::new(&payload_buf)
29649 } else {
29650 Bytes::new(__input)
29651 };
29652 let mut __struct = Self::default();
29653 __struct.param_value = buf.get_f32_le();
29654 __struct.param_count = buf.get_u16_le();
29655 __struct.param_index = buf.get_u16_le();
29656 for v in &mut __struct.param_id {
29657 let val = buf.get_u8();
29658 *v = val;
29659 }
29660 let tmp = buf.get_u8();
29661 __struct.param_type =
29662 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29663 enum_type: "MavParamType",
29664 value: tmp as u32,
29665 })?;
29666 Ok(__struct)
29667 }
29668 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29669 let mut __tmp = BytesMut::new(bytes);
29670 #[allow(clippy::absurd_extreme_comparisons)]
29671 #[allow(unused_comparisons)]
29672 if __tmp.remaining() < Self::ENCODED_LEN {
29673 panic!(
29674 "buffer is too small (need {} bytes, but got {})",
29675 Self::ENCODED_LEN,
29676 __tmp.remaining(),
29677 )
29678 }
29679 __tmp.put_f32_le(self.param_value);
29680 __tmp.put_u16_le(self.param_count);
29681 __tmp.put_u16_le(self.param_index);
29682 for val in &self.param_id {
29683 __tmp.put_u8(*val);
29684 }
29685 __tmp.put_u8(self.param_type as u8);
29686 if matches!(version, MavlinkVersion::V2) {
29687 let len = __tmp.len();
29688 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29689 } else {
29690 __tmp.len()
29691 }
29692 }
29693}
29694#[doc = "id: 287"]
29695#[doc = "Set gimbal manager pitch and yaw angles (high rate message). This message is to be sent to the gimbal manager (e.g. from a ground station) and will be ignored by gimbal devices. Angles and rates can be set to NaN according to use case. Use MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAW for low-rate adjustments that require confirmation."]
29696#[derive(Debug, Clone, PartialEq)]
29697#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29698#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29699pub struct GIMBAL_MANAGER_SET_PITCHYAW_DATA {
29700 #[doc = "High level gimbal manager flags to use."]
29701 pub flags: GimbalManagerFlags,
29702 #[doc = "Pitch angle (positive: up, negative: down, NaN to be ignored)."]
29703 pub pitch: f32,
29704 #[doc = "Yaw angle (positive: to the right, negative: to the left, NaN to be ignored)."]
29705 pub yaw: f32,
29706 #[doc = "Pitch angular rate (positive: up, negative: down, NaN to be ignored)."]
29707 pub pitch_rate: f32,
29708 #[doc = "Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored)."]
29709 pub yaw_rate: f32,
29710 #[doc = "System ID"]
29711 pub target_system: u8,
29712 #[doc = "Component ID"]
29713 pub target_component: u8,
29714 #[doc = "Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals)."]
29715 pub gimbal_device_id: u8,
29716}
29717impl GIMBAL_MANAGER_SET_PITCHYAW_DATA {
29718 pub const ENCODED_LEN: usize = 23usize;
29719 pub const DEFAULT: Self = Self {
29720 flags: GimbalManagerFlags::DEFAULT,
29721 pitch: 0.0_f32,
29722 yaw: 0.0_f32,
29723 pitch_rate: 0.0_f32,
29724 yaw_rate: 0.0_f32,
29725 target_system: 0_u8,
29726 target_component: 0_u8,
29727 gimbal_device_id: 0_u8,
29728 };
29729 #[cfg(feature = "arbitrary")]
29730 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29731 use arbitrary::{Arbitrary, Unstructured};
29732 let mut buf = [0u8; 1024];
29733 rng.fill_bytes(&mut buf);
29734 let mut unstructured = Unstructured::new(&buf);
29735 Self::arbitrary(&mut unstructured).unwrap_or_default()
29736 }
29737}
29738impl Default for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
29739 fn default() -> Self {
29740 Self::DEFAULT.clone()
29741 }
29742}
29743impl MessageData for GIMBAL_MANAGER_SET_PITCHYAW_DATA {
29744 type Message = MavMessage;
29745 const ID: u32 = 287u32;
29746 const NAME: &'static str = "GIMBAL_MANAGER_SET_PITCHYAW";
29747 const EXTRA_CRC: u8 = 1u8;
29748 const ENCODED_LEN: usize = 23usize;
29749 fn deser(
29750 _version: MavlinkVersion,
29751 __input: &[u8],
29752 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29753 let avail_len = __input.len();
29754 let mut payload_buf = [0; Self::ENCODED_LEN];
29755 let mut buf = if avail_len < Self::ENCODED_LEN {
29756 payload_buf[0..avail_len].copy_from_slice(__input);
29757 Bytes::new(&payload_buf)
29758 } else {
29759 Bytes::new(__input)
29760 };
29761 let mut __struct = Self::default();
29762 let tmp = buf.get_u32_le();
29763 __struct.flags = GimbalManagerFlags::from_bits(tmp & GimbalManagerFlags::all().bits())
29764 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
29765 flag_type: "GimbalManagerFlags",
29766 value: tmp as u32,
29767 })?;
29768 __struct.pitch = buf.get_f32_le();
29769 __struct.yaw = buf.get_f32_le();
29770 __struct.pitch_rate = buf.get_f32_le();
29771 __struct.yaw_rate = buf.get_f32_le();
29772 __struct.target_system = buf.get_u8();
29773 __struct.target_component = buf.get_u8();
29774 __struct.gimbal_device_id = buf.get_u8();
29775 Ok(__struct)
29776 }
29777 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29778 let mut __tmp = BytesMut::new(bytes);
29779 #[allow(clippy::absurd_extreme_comparisons)]
29780 #[allow(unused_comparisons)]
29781 if __tmp.remaining() < Self::ENCODED_LEN {
29782 panic!(
29783 "buffer is too small (need {} bytes, but got {})",
29784 Self::ENCODED_LEN,
29785 __tmp.remaining(),
29786 )
29787 }
29788 __tmp.put_u32_le(self.flags.bits());
29789 __tmp.put_f32_le(self.pitch);
29790 __tmp.put_f32_le(self.yaw);
29791 __tmp.put_f32_le(self.pitch_rate);
29792 __tmp.put_f32_le(self.yaw_rate);
29793 __tmp.put_u8(self.target_system);
29794 __tmp.put_u8(self.target_component);
29795 __tmp.put_u8(self.gimbal_device_id);
29796 if matches!(version, MavlinkVersion::V2) {
29797 let len = __tmp.len();
29798 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29799 } else {
29800 __tmp.len()
29801 }
29802 }
29803}
29804#[doc = "id: 411"]
29805#[doc = "Regular broadcast for the current latest event sequence number for a component. This is used to check for dropped events."]
29806#[derive(Debug, Clone, PartialEq)]
29807#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29808#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29809pub struct CURRENT_EVENT_SEQUENCE_DATA {
29810 #[doc = "Sequence number."]
29811 pub sequence: u16,
29812 #[doc = "Flag bitset."]
29813 pub flags: MavEventCurrentSequenceFlags,
29814}
29815impl CURRENT_EVENT_SEQUENCE_DATA {
29816 pub const ENCODED_LEN: usize = 3usize;
29817 pub const DEFAULT: Self = Self {
29818 sequence: 0_u16,
29819 flags: MavEventCurrentSequenceFlags::DEFAULT,
29820 };
29821 #[cfg(feature = "arbitrary")]
29822 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29823 use arbitrary::{Arbitrary, Unstructured};
29824 let mut buf = [0u8; 1024];
29825 rng.fill_bytes(&mut buf);
29826 let mut unstructured = Unstructured::new(&buf);
29827 Self::arbitrary(&mut unstructured).unwrap_or_default()
29828 }
29829}
29830impl Default for CURRENT_EVENT_SEQUENCE_DATA {
29831 fn default() -> Self {
29832 Self::DEFAULT.clone()
29833 }
29834}
29835impl MessageData for CURRENT_EVENT_SEQUENCE_DATA {
29836 type Message = MavMessage;
29837 const ID: u32 = 411u32;
29838 const NAME: &'static str = "CURRENT_EVENT_SEQUENCE";
29839 const EXTRA_CRC: u8 = 106u8;
29840 const ENCODED_LEN: usize = 3usize;
29841 fn deser(
29842 _version: MavlinkVersion,
29843 __input: &[u8],
29844 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29845 let avail_len = __input.len();
29846 let mut payload_buf = [0; Self::ENCODED_LEN];
29847 let mut buf = if avail_len < Self::ENCODED_LEN {
29848 payload_buf[0..avail_len].copy_from_slice(__input);
29849 Bytes::new(&payload_buf)
29850 } else {
29851 Bytes::new(__input)
29852 };
29853 let mut __struct = Self::default();
29854 __struct.sequence = buf.get_u16_le();
29855 let tmp = buf.get_u8();
29856 __struct.flags =
29857 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
29858 enum_type: "MavEventCurrentSequenceFlags",
29859 value: tmp as u32,
29860 })?;
29861 Ok(__struct)
29862 }
29863 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
29864 let mut __tmp = BytesMut::new(bytes);
29865 #[allow(clippy::absurd_extreme_comparisons)]
29866 #[allow(unused_comparisons)]
29867 if __tmp.remaining() < Self::ENCODED_LEN {
29868 panic!(
29869 "buffer is too small (need {} bytes, but got {})",
29870 Self::ENCODED_LEN,
29871 __tmp.remaining(),
29872 )
29873 }
29874 __tmp.put_u16_le(self.sequence);
29875 __tmp.put_u8(self.flags as u8);
29876 if matches!(version, MavlinkVersion::V2) {
29877 let len = __tmp.len();
29878 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
29879 } else {
29880 __tmp.len()
29881 }
29882 }
29883}
29884#[doc = "id: 259"]
29885#[doc = "Information about a camera. Can be requested with a MAV_CMD_REQUEST_MESSAGE command."]
29886#[derive(Debug, Clone, PartialEq)]
29887#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
29888#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
29889pub struct CAMERA_INFORMATION_DATA {
29890 #[doc = "Timestamp (time since system boot)."]
29891 pub time_boot_ms: u32,
29892 #[doc = "0xff). Use 0 if not known."]
29893 pub firmware_version: u32,
29894 #[doc = "Focal length. Use NaN if not known."]
29895 pub focal_length: f32,
29896 #[doc = "Image sensor size horizontal. Use NaN if not known."]
29897 pub sensor_size_h: f32,
29898 #[doc = "Image sensor size vertical. Use NaN if not known."]
29899 pub sensor_size_v: f32,
29900 #[doc = "Bitmap of camera capability flags."]
29901 pub flags: CameraCapFlags,
29902 #[doc = "Horizontal image resolution. Use 0 if not known."]
29903 pub resolution_h: u16,
29904 #[doc = "Vertical image resolution. Use 0 if not known."]
29905 pub resolution_v: u16,
29906 #[doc = "Camera definition version (iteration). Use 0 if not known."]
29907 pub cam_definition_version: u16,
29908 #[doc = "Name of the camera vendor"]
29909 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29910 pub vendor_name: [u8; 32],
29911 #[doc = "Name of the camera model"]
29912 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29913 pub model_name: [u8; 32],
29914 #[doc = "Reserved for a lens ID. Use 0 if not known."]
29915 pub lens_id: u8,
29916 #[doc = "Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol). The definition file may be xz compressed, which will be indicated by the file extension .xml.xz (a GCS that implements the protocol must support decompressing the file). The string needs to be zero terminated. Use a zero-length string if not known."]
29917 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
29918 pub cam_definition_uri: [u8; 140],
29919 #[doc = "Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera."]
29920 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29921 pub gimbal_device_id: u8,
29922 #[doc = "Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id)."]
29923 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
29924 pub camera_device_id: u8,
29925}
29926impl CAMERA_INFORMATION_DATA {
29927 pub const ENCODED_LEN: usize = 237usize;
29928 pub const DEFAULT: Self = Self {
29929 time_boot_ms: 0_u32,
29930 firmware_version: 0_u32,
29931 focal_length: 0.0_f32,
29932 sensor_size_h: 0.0_f32,
29933 sensor_size_v: 0.0_f32,
29934 flags: CameraCapFlags::DEFAULT,
29935 resolution_h: 0_u16,
29936 resolution_v: 0_u16,
29937 cam_definition_version: 0_u16,
29938 vendor_name: [0_u8; 32usize],
29939 model_name: [0_u8; 32usize],
29940 lens_id: 0_u8,
29941 cam_definition_uri: [0_u8; 140usize],
29942 gimbal_device_id: 0_u8,
29943 camera_device_id: 0_u8,
29944 };
29945 #[cfg(feature = "arbitrary")]
29946 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
29947 use arbitrary::{Arbitrary, Unstructured};
29948 let mut buf = [0u8; 1024];
29949 rng.fill_bytes(&mut buf);
29950 let mut unstructured = Unstructured::new(&buf);
29951 Self::arbitrary(&mut unstructured).unwrap_or_default()
29952 }
29953}
29954impl Default for CAMERA_INFORMATION_DATA {
29955 fn default() -> Self {
29956 Self::DEFAULT.clone()
29957 }
29958}
29959impl MessageData for CAMERA_INFORMATION_DATA {
29960 type Message = MavMessage;
29961 const ID: u32 = 259u32;
29962 const NAME: &'static str = "CAMERA_INFORMATION";
29963 const EXTRA_CRC: u8 = 92u8;
29964 const ENCODED_LEN: usize = 237usize;
29965 fn deser(
29966 _version: MavlinkVersion,
29967 __input: &[u8],
29968 ) -> Result<Self, ::mavlink_core::error::ParserError> {
29969 let avail_len = __input.len();
29970 let mut payload_buf = [0; Self::ENCODED_LEN];
29971 let mut buf = if avail_len < Self::ENCODED_LEN {
29972 payload_buf[0..avail_len].copy_from_slice(__input);
29973 Bytes::new(&payload_buf)
29974 } else {
29975 Bytes::new(__input)
29976 };
29977 let mut __struct = Self::default();
29978 __struct.time_boot_ms = buf.get_u32_le();
29979 __struct.firmware_version = buf.get_u32_le();
29980 __struct.focal_length = buf.get_f32_le();
29981 __struct.sensor_size_h = buf.get_f32_le();
29982 __struct.sensor_size_v = buf.get_f32_le();
29983 let tmp = buf.get_u32_le();
29984 __struct.flags = CameraCapFlags::from_bits(tmp & CameraCapFlags::all().bits()).ok_or(
29985 ::mavlink_core::error::ParserError::InvalidFlag {
29986 flag_type: "CameraCapFlags",
29987 value: tmp as u32,
29988 },
29989 )?;
29990 __struct.resolution_h = buf.get_u16_le();
29991 __struct.resolution_v = buf.get_u16_le();
29992 __struct.cam_definition_version = buf.get_u16_le();
29993 for v in &mut __struct.vendor_name {
29994 let val = buf.get_u8();
29995 *v = val;
29996 }
29997 for v in &mut __struct.model_name {
29998 let val = buf.get_u8();
29999 *v = val;
30000 }
30001 __struct.lens_id = buf.get_u8();
30002 for v in &mut __struct.cam_definition_uri {
30003 let val = buf.get_u8();
30004 *v = val;
30005 }
30006 __struct.gimbal_device_id = buf.get_u8();
30007 __struct.camera_device_id = buf.get_u8();
30008 Ok(__struct)
30009 }
30010 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30011 let mut __tmp = BytesMut::new(bytes);
30012 #[allow(clippy::absurd_extreme_comparisons)]
30013 #[allow(unused_comparisons)]
30014 if __tmp.remaining() < Self::ENCODED_LEN {
30015 panic!(
30016 "buffer is too small (need {} bytes, but got {})",
30017 Self::ENCODED_LEN,
30018 __tmp.remaining(),
30019 )
30020 }
30021 __tmp.put_u32_le(self.time_boot_ms);
30022 __tmp.put_u32_le(self.firmware_version);
30023 __tmp.put_f32_le(self.focal_length);
30024 __tmp.put_f32_le(self.sensor_size_h);
30025 __tmp.put_f32_le(self.sensor_size_v);
30026 __tmp.put_u32_le(self.flags.bits());
30027 __tmp.put_u16_le(self.resolution_h);
30028 __tmp.put_u16_le(self.resolution_v);
30029 __tmp.put_u16_le(self.cam_definition_version);
30030 for val in &self.vendor_name {
30031 __tmp.put_u8(*val);
30032 }
30033 for val in &self.model_name {
30034 __tmp.put_u8(*val);
30035 }
30036 __tmp.put_u8(self.lens_id);
30037 for val in &self.cam_definition_uri {
30038 __tmp.put_u8(*val);
30039 }
30040 __tmp.put_u8(self.gimbal_device_id);
30041 __tmp.put_u8(self.camera_device_id);
30042 if matches!(version, MavlinkVersion::V2) {
30043 let len = __tmp.len();
30044 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30045 } else {
30046 __tmp.len()
30047 }
30048 }
30049}
30050#[doc = "id: 12905"]
30051#[doc = "Data for filling the OpenDroneID Operator ID message, which contains the CAA (Civil Aviation Authority) issued operator ID."]
30052#[derive(Debug, Clone, PartialEq)]
30053#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30054#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30055pub struct OPEN_DRONE_ID_OPERATOR_ID_DATA {
30056 #[doc = "System ID (0 for broadcast)."]
30057 pub target_system: u8,
30058 #[doc = "Component ID (0 for broadcast)."]
30059 pub target_component: u8,
30060 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
30061 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30062 pub id_or_mac: [u8; 20],
30063 #[doc = "Indicates the type of the operator_id field."]
30064 pub operator_id_type: MavOdidOperatorIdType,
30065 #[doc = "Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field."]
30066 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30067 pub operator_id: [u8; 20],
30068}
30069impl OPEN_DRONE_ID_OPERATOR_ID_DATA {
30070 pub const ENCODED_LEN: usize = 43usize;
30071 pub const DEFAULT: Self = Self {
30072 target_system: 0_u8,
30073 target_component: 0_u8,
30074 id_or_mac: [0_u8; 20usize],
30075 operator_id_type: MavOdidOperatorIdType::DEFAULT,
30076 operator_id: [0_u8; 20usize],
30077 };
30078 #[cfg(feature = "arbitrary")]
30079 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30080 use arbitrary::{Arbitrary, Unstructured};
30081 let mut buf = [0u8; 1024];
30082 rng.fill_bytes(&mut buf);
30083 let mut unstructured = Unstructured::new(&buf);
30084 Self::arbitrary(&mut unstructured).unwrap_or_default()
30085 }
30086}
30087impl Default for OPEN_DRONE_ID_OPERATOR_ID_DATA {
30088 fn default() -> Self {
30089 Self::DEFAULT.clone()
30090 }
30091}
30092impl MessageData for OPEN_DRONE_ID_OPERATOR_ID_DATA {
30093 type Message = MavMessage;
30094 const ID: u32 = 12905u32;
30095 const NAME: &'static str = "OPEN_DRONE_ID_OPERATOR_ID";
30096 const EXTRA_CRC: u8 = 49u8;
30097 const ENCODED_LEN: usize = 43usize;
30098 fn deser(
30099 _version: MavlinkVersion,
30100 __input: &[u8],
30101 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30102 let avail_len = __input.len();
30103 let mut payload_buf = [0; Self::ENCODED_LEN];
30104 let mut buf = if avail_len < Self::ENCODED_LEN {
30105 payload_buf[0..avail_len].copy_from_slice(__input);
30106 Bytes::new(&payload_buf)
30107 } else {
30108 Bytes::new(__input)
30109 };
30110 let mut __struct = Self::default();
30111 __struct.target_system = buf.get_u8();
30112 __struct.target_component = buf.get_u8();
30113 for v in &mut __struct.id_or_mac {
30114 let val = buf.get_u8();
30115 *v = val;
30116 }
30117 let tmp = buf.get_u8();
30118 __struct.operator_id_type =
30119 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30120 enum_type: "MavOdidOperatorIdType",
30121 value: tmp as u32,
30122 })?;
30123 for v in &mut __struct.operator_id {
30124 let val = buf.get_u8();
30125 *v = val;
30126 }
30127 Ok(__struct)
30128 }
30129 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30130 let mut __tmp = BytesMut::new(bytes);
30131 #[allow(clippy::absurd_extreme_comparisons)]
30132 #[allow(unused_comparisons)]
30133 if __tmp.remaining() < Self::ENCODED_LEN {
30134 panic!(
30135 "buffer is too small (need {} bytes, but got {})",
30136 Self::ENCODED_LEN,
30137 __tmp.remaining(),
30138 )
30139 }
30140 __tmp.put_u8(self.target_system);
30141 __tmp.put_u8(self.target_component);
30142 for val in &self.id_or_mac {
30143 __tmp.put_u8(*val);
30144 }
30145 __tmp.put_u8(self.operator_id_type as u8);
30146 for val in &self.operator_id {
30147 __tmp.put_u8(*val);
30148 }
30149 if matches!(version, MavlinkVersion::V2) {
30150 let len = __tmp.len();
30151 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30152 } else {
30153 __tmp.len()
30154 }
30155 }
30156}
30157#[doc = "id: 395"]
30158#[doc = "Component information message, which may be requested using MAV_CMD_REQUEST_MESSAGE."]
30159#[derive(Debug, Clone, PartialEq)]
30160#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30161#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30162pub struct COMPONENT_INFORMATION_DATA {
30163 #[doc = "Timestamp (time since system boot)."]
30164 pub time_boot_ms: u32,
30165 #[doc = "CRC32 of the general metadata file (general_metadata_uri)."]
30166 pub general_metadata_file_crc: u32,
30167 #[doc = "CRC32 of peripherals metadata file (peripherals_metadata_uri)."]
30168 pub peripherals_metadata_file_crc: u32,
30169 #[doc = "MAVLink FTP URI for the general metadata file (COMP_METADATA_TYPE_GENERAL), which may be compressed with xz. The file contains general component metadata, and may contain URI links for additional metadata (see COMP_METADATA_TYPE). The information is static from boot, and may be generated at compile time. The string needs to be zero terminated."]
30170 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30171 pub general_metadata_uri: [u8; 100],
30172 #[doc = "(Optional) MAVLink FTP URI for the peripherals metadata file (COMP_METADATA_TYPE_PERIPHERALS), which may be compressed with xz. This contains data about \"attached components\" such as UAVCAN nodes. The peripherals are in a separate file because the information must be generated dynamically at runtime. The string needs to be zero terminated."]
30173 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30174 pub peripherals_metadata_uri: [u8; 100],
30175}
30176impl COMPONENT_INFORMATION_DATA {
30177 pub const ENCODED_LEN: usize = 212usize;
30178 pub const DEFAULT: Self = Self {
30179 time_boot_ms: 0_u32,
30180 general_metadata_file_crc: 0_u32,
30181 peripherals_metadata_file_crc: 0_u32,
30182 general_metadata_uri: [0_u8; 100usize],
30183 peripherals_metadata_uri: [0_u8; 100usize],
30184 };
30185 #[cfg(feature = "arbitrary")]
30186 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30187 use arbitrary::{Arbitrary, Unstructured};
30188 let mut buf = [0u8; 1024];
30189 rng.fill_bytes(&mut buf);
30190 let mut unstructured = Unstructured::new(&buf);
30191 Self::arbitrary(&mut unstructured).unwrap_or_default()
30192 }
30193}
30194impl Default for COMPONENT_INFORMATION_DATA {
30195 fn default() -> Self {
30196 Self::DEFAULT.clone()
30197 }
30198}
30199impl MessageData for COMPONENT_INFORMATION_DATA {
30200 type Message = MavMessage;
30201 const ID: u32 = 395u32;
30202 const NAME: &'static str = "COMPONENT_INFORMATION";
30203 const EXTRA_CRC: u8 = 0u8;
30204 const ENCODED_LEN: usize = 212usize;
30205 fn deser(
30206 _version: MavlinkVersion,
30207 __input: &[u8],
30208 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30209 let avail_len = __input.len();
30210 let mut payload_buf = [0; Self::ENCODED_LEN];
30211 let mut buf = if avail_len < Self::ENCODED_LEN {
30212 payload_buf[0..avail_len].copy_from_slice(__input);
30213 Bytes::new(&payload_buf)
30214 } else {
30215 Bytes::new(__input)
30216 };
30217 let mut __struct = Self::default();
30218 __struct.time_boot_ms = buf.get_u32_le();
30219 __struct.general_metadata_file_crc = buf.get_u32_le();
30220 __struct.peripherals_metadata_file_crc = buf.get_u32_le();
30221 for v in &mut __struct.general_metadata_uri {
30222 let val = buf.get_u8();
30223 *v = val;
30224 }
30225 for v in &mut __struct.peripherals_metadata_uri {
30226 let val = buf.get_u8();
30227 *v = val;
30228 }
30229 Ok(__struct)
30230 }
30231 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30232 let mut __tmp = BytesMut::new(bytes);
30233 #[allow(clippy::absurd_extreme_comparisons)]
30234 #[allow(unused_comparisons)]
30235 if __tmp.remaining() < Self::ENCODED_LEN {
30236 panic!(
30237 "buffer is too small (need {} bytes, but got {})",
30238 Self::ENCODED_LEN,
30239 __tmp.remaining(),
30240 )
30241 }
30242 __tmp.put_u32_le(self.time_boot_ms);
30243 __tmp.put_u32_le(self.general_metadata_file_crc);
30244 __tmp.put_u32_le(self.peripherals_metadata_file_crc);
30245 for val in &self.general_metadata_uri {
30246 __tmp.put_u8(*val);
30247 }
30248 for val in &self.peripherals_metadata_uri {
30249 __tmp.put_u8(*val);
30250 }
30251 if matches!(version, MavlinkVersion::V2) {
30252 let len = __tmp.len();
30253 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30254 } else {
30255 __tmp.len()
30256 }
30257 }
30258}
30259#[doc = "id: 76"]
30260#[doc = "Send a command with up to seven parameters to the MAV. COMMAND_INT is generally preferred when sending MAV_CMD commands that include positional information; it offers higher precision and allows the MAV_FRAME to be specified (which may otherwise be ambiguous, particularly for altitude). The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
30261#[derive(Debug, Clone, PartialEq)]
30262#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30263#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30264pub struct COMMAND_LONG_DATA {
30265 #[doc = "Parameter 1 (for the specific command)."]
30266 pub param1: f32,
30267 #[doc = "Parameter 2 (for the specific command)."]
30268 pub param2: f32,
30269 #[doc = "Parameter 3 (for the specific command)."]
30270 pub param3: f32,
30271 #[doc = "Parameter 4 (for the specific command)."]
30272 pub param4: f32,
30273 #[doc = "Parameter 5 (for the specific command)."]
30274 pub param5: f32,
30275 #[doc = "Parameter 6 (for the specific command)."]
30276 pub param6: f32,
30277 #[doc = "Parameter 7 (for the specific command)."]
30278 pub param7: f32,
30279 #[doc = "Command ID (of command to send)."]
30280 pub command: MavCmd,
30281 #[doc = "System which should execute the command"]
30282 pub target_system: u8,
30283 #[doc = "Component which should execute the command, 0 for all components"]
30284 pub target_component: u8,
30285 #[doc = "0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)"]
30286 pub confirmation: u8,
30287}
30288impl COMMAND_LONG_DATA {
30289 pub const ENCODED_LEN: usize = 33usize;
30290 pub const DEFAULT: Self = Self {
30291 param1: 0.0_f32,
30292 param2: 0.0_f32,
30293 param3: 0.0_f32,
30294 param4: 0.0_f32,
30295 param5: 0.0_f32,
30296 param6: 0.0_f32,
30297 param7: 0.0_f32,
30298 command: MavCmd::DEFAULT,
30299 target_system: 0_u8,
30300 target_component: 0_u8,
30301 confirmation: 0_u8,
30302 };
30303 #[cfg(feature = "arbitrary")]
30304 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30305 use arbitrary::{Arbitrary, Unstructured};
30306 let mut buf = [0u8; 1024];
30307 rng.fill_bytes(&mut buf);
30308 let mut unstructured = Unstructured::new(&buf);
30309 Self::arbitrary(&mut unstructured).unwrap_or_default()
30310 }
30311}
30312impl Default for COMMAND_LONG_DATA {
30313 fn default() -> Self {
30314 Self::DEFAULT.clone()
30315 }
30316}
30317impl MessageData for COMMAND_LONG_DATA {
30318 type Message = MavMessage;
30319 const ID: u32 = 76u32;
30320 const NAME: &'static str = "COMMAND_LONG";
30321 const EXTRA_CRC: u8 = 152u8;
30322 const ENCODED_LEN: usize = 33usize;
30323 fn deser(
30324 _version: MavlinkVersion,
30325 __input: &[u8],
30326 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30327 let avail_len = __input.len();
30328 let mut payload_buf = [0; Self::ENCODED_LEN];
30329 let mut buf = if avail_len < Self::ENCODED_LEN {
30330 payload_buf[0..avail_len].copy_from_slice(__input);
30331 Bytes::new(&payload_buf)
30332 } else {
30333 Bytes::new(__input)
30334 };
30335 let mut __struct = Self::default();
30336 __struct.param1 = buf.get_f32_le();
30337 __struct.param2 = buf.get_f32_le();
30338 __struct.param3 = buf.get_f32_le();
30339 __struct.param4 = buf.get_f32_le();
30340 __struct.param5 = buf.get_f32_le();
30341 __struct.param6 = buf.get_f32_le();
30342 __struct.param7 = buf.get_f32_le();
30343 let tmp = buf.get_u16_le();
30344 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
30345 ::mavlink_core::error::ParserError::InvalidEnum {
30346 enum_type: "MavCmd",
30347 value: tmp as u32,
30348 },
30349 )?;
30350 __struct.target_system = buf.get_u8();
30351 __struct.target_component = buf.get_u8();
30352 __struct.confirmation = buf.get_u8();
30353 Ok(__struct)
30354 }
30355 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30356 let mut __tmp = BytesMut::new(bytes);
30357 #[allow(clippy::absurd_extreme_comparisons)]
30358 #[allow(unused_comparisons)]
30359 if __tmp.remaining() < Self::ENCODED_LEN {
30360 panic!(
30361 "buffer is too small (need {} bytes, but got {})",
30362 Self::ENCODED_LEN,
30363 __tmp.remaining(),
30364 )
30365 }
30366 __tmp.put_f32_le(self.param1);
30367 __tmp.put_f32_le(self.param2);
30368 __tmp.put_f32_le(self.param3);
30369 __tmp.put_f32_le(self.param4);
30370 __tmp.put_f32_le(self.param5);
30371 __tmp.put_f32_le(self.param6);
30372 __tmp.put_f32_le(self.param7);
30373 __tmp.put_u16_le(self.command as u16);
30374 __tmp.put_u8(self.target_system);
30375 __tmp.put_u8(self.target_component);
30376 __tmp.put_u8(self.confirmation);
30377 if matches!(version, MavlinkVersion::V2) {
30378 let len = __tmp.len();
30379 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30380 } else {
30381 __tmp.len()
30382 }
30383 }
30384}
30385#[doc = "id: 323"]
30386#[doc = "Set a parameter value. In order to deal with message loss (and retransmission of PARAM_EXT_SET), when setting a parameter value and the new value is the same as the current value, you will immediately get a PARAM_ACK_ACCEPTED response. If the current state is PARAM_ACK_IN_PROGRESS, you will accordingly receive a PARAM_ACK_IN_PROGRESS in response."]
30387#[derive(Debug, Clone, PartialEq)]
30388#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30389#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30390pub struct PARAM_EXT_SET_DATA {
30391 #[doc = "System ID"]
30392 pub target_system: u8,
30393 #[doc = "Component ID"]
30394 pub target_component: u8,
30395 #[doc = "Parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
30396 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30397 pub param_id: [u8; 16],
30398 #[doc = "Parameter value"]
30399 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30400 pub param_value: [u8; 128],
30401 #[doc = "Parameter type."]
30402 pub param_type: MavParamExtType,
30403}
30404impl PARAM_EXT_SET_DATA {
30405 pub const ENCODED_LEN: usize = 147usize;
30406 pub const DEFAULT: Self = Self {
30407 target_system: 0_u8,
30408 target_component: 0_u8,
30409 param_id: [0_u8; 16usize],
30410 param_value: [0_u8; 128usize],
30411 param_type: MavParamExtType::DEFAULT,
30412 };
30413 #[cfg(feature = "arbitrary")]
30414 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30415 use arbitrary::{Arbitrary, Unstructured};
30416 let mut buf = [0u8; 1024];
30417 rng.fill_bytes(&mut buf);
30418 let mut unstructured = Unstructured::new(&buf);
30419 Self::arbitrary(&mut unstructured).unwrap_or_default()
30420 }
30421}
30422impl Default for PARAM_EXT_SET_DATA {
30423 fn default() -> Self {
30424 Self::DEFAULT.clone()
30425 }
30426}
30427impl MessageData for PARAM_EXT_SET_DATA {
30428 type Message = MavMessage;
30429 const ID: u32 = 323u32;
30430 const NAME: &'static str = "PARAM_EXT_SET";
30431 const EXTRA_CRC: u8 = 78u8;
30432 const ENCODED_LEN: usize = 147usize;
30433 fn deser(
30434 _version: MavlinkVersion,
30435 __input: &[u8],
30436 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30437 let avail_len = __input.len();
30438 let mut payload_buf = [0; Self::ENCODED_LEN];
30439 let mut buf = if avail_len < Self::ENCODED_LEN {
30440 payload_buf[0..avail_len].copy_from_slice(__input);
30441 Bytes::new(&payload_buf)
30442 } else {
30443 Bytes::new(__input)
30444 };
30445 let mut __struct = Self::default();
30446 __struct.target_system = buf.get_u8();
30447 __struct.target_component = buf.get_u8();
30448 for v in &mut __struct.param_id {
30449 let val = buf.get_u8();
30450 *v = val;
30451 }
30452 for v in &mut __struct.param_value {
30453 let val = buf.get_u8();
30454 *v = val;
30455 }
30456 let tmp = buf.get_u8();
30457 __struct.param_type =
30458 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30459 enum_type: "MavParamExtType",
30460 value: tmp as u32,
30461 })?;
30462 Ok(__struct)
30463 }
30464 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30465 let mut __tmp = BytesMut::new(bytes);
30466 #[allow(clippy::absurd_extreme_comparisons)]
30467 #[allow(unused_comparisons)]
30468 if __tmp.remaining() < Self::ENCODED_LEN {
30469 panic!(
30470 "buffer is too small (need {} bytes, but got {})",
30471 Self::ENCODED_LEN,
30472 __tmp.remaining(),
30473 )
30474 }
30475 __tmp.put_u8(self.target_system);
30476 __tmp.put_u8(self.target_component);
30477 for val in &self.param_id {
30478 __tmp.put_u8(*val);
30479 }
30480 for val in &self.param_value {
30481 __tmp.put_u8(*val);
30482 }
30483 __tmp.put_u8(self.param_type as u8);
30484 if matches!(version, MavlinkVersion::V2) {
30485 let len = __tmp.len();
30486 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30487 } else {
30488 __tmp.len()
30489 }
30490 }
30491}
30492#[doc = "id: 232"]
30493#[doc = "GPS sensor input message. This is a raw sensor value sent by the GPS. This is NOT the global position estimate of the system."]
30494#[derive(Debug, Clone, PartialEq)]
30495#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30496#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30497pub struct GPS_INPUT_DATA {
30498 #[doc = "Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number."]
30499 pub time_usec: u64,
30500 #[doc = "GPS time (from start of GPS week)"]
30501 pub time_week_ms: u32,
30502 #[doc = "Latitude (WGS84)"]
30503 pub lat: i32,
30504 #[doc = "Longitude (WGS84)"]
30505 pub lon: i32,
30506 #[doc = "Altitude (MSL). Positive for up."]
30507 pub alt: f32,
30508 #[doc = "GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX"]
30509 pub hdop: f32,
30510 #[doc = "GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX"]
30511 pub vdop: f32,
30512 #[doc = "GPS velocity in north direction in earth-fixed NED frame"]
30513 pub vn: f32,
30514 #[doc = "GPS velocity in east direction in earth-fixed NED frame"]
30515 pub ve: f32,
30516 #[doc = "GPS velocity in down direction in earth-fixed NED frame"]
30517 pub vd: f32,
30518 #[doc = "GPS speed accuracy"]
30519 pub speed_accuracy: f32,
30520 #[doc = "GPS horizontal accuracy"]
30521 pub horiz_accuracy: f32,
30522 #[doc = "GPS vertical accuracy"]
30523 pub vert_accuracy: f32,
30524 #[doc = "Bitmap indicating which GPS input flags fields to ignore. All other fields must be provided."]
30525 pub ignore_flags: GpsInputIgnoreFlags,
30526 #[doc = "GPS week number"]
30527 pub time_week: u16,
30528 #[doc = "ID of the GPS for multiple GPS inputs"]
30529 pub gps_id: u8,
30530 #[doc = "0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK"]
30531 pub fix_type: u8,
30532 #[doc = "Number of satellites visible."]
30533 pub satellites_visible: u8,
30534 #[doc = "Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north"]
30535 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30536 pub yaw: u16,
30537}
30538impl GPS_INPUT_DATA {
30539 pub const ENCODED_LEN: usize = 65usize;
30540 pub const DEFAULT: Self = Self {
30541 time_usec: 0_u64,
30542 time_week_ms: 0_u32,
30543 lat: 0_i32,
30544 lon: 0_i32,
30545 alt: 0.0_f32,
30546 hdop: 0.0_f32,
30547 vdop: 0.0_f32,
30548 vn: 0.0_f32,
30549 ve: 0.0_f32,
30550 vd: 0.0_f32,
30551 speed_accuracy: 0.0_f32,
30552 horiz_accuracy: 0.0_f32,
30553 vert_accuracy: 0.0_f32,
30554 ignore_flags: GpsInputIgnoreFlags::DEFAULT,
30555 time_week: 0_u16,
30556 gps_id: 0_u8,
30557 fix_type: 0_u8,
30558 satellites_visible: 0_u8,
30559 yaw: 0_u16,
30560 };
30561 #[cfg(feature = "arbitrary")]
30562 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30563 use arbitrary::{Arbitrary, Unstructured};
30564 let mut buf = [0u8; 1024];
30565 rng.fill_bytes(&mut buf);
30566 let mut unstructured = Unstructured::new(&buf);
30567 Self::arbitrary(&mut unstructured).unwrap_or_default()
30568 }
30569}
30570impl Default for GPS_INPUT_DATA {
30571 fn default() -> Self {
30572 Self::DEFAULT.clone()
30573 }
30574}
30575impl MessageData for GPS_INPUT_DATA {
30576 type Message = MavMessage;
30577 const ID: u32 = 232u32;
30578 const NAME: &'static str = "GPS_INPUT";
30579 const EXTRA_CRC: u8 = 151u8;
30580 const ENCODED_LEN: usize = 65usize;
30581 fn deser(
30582 _version: MavlinkVersion,
30583 __input: &[u8],
30584 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30585 let avail_len = __input.len();
30586 let mut payload_buf = [0; Self::ENCODED_LEN];
30587 let mut buf = if avail_len < Self::ENCODED_LEN {
30588 payload_buf[0..avail_len].copy_from_slice(__input);
30589 Bytes::new(&payload_buf)
30590 } else {
30591 Bytes::new(__input)
30592 };
30593 let mut __struct = Self::default();
30594 __struct.time_usec = buf.get_u64_le();
30595 __struct.time_week_ms = buf.get_u32_le();
30596 __struct.lat = buf.get_i32_le();
30597 __struct.lon = buf.get_i32_le();
30598 __struct.alt = buf.get_f32_le();
30599 __struct.hdop = buf.get_f32_le();
30600 __struct.vdop = buf.get_f32_le();
30601 __struct.vn = buf.get_f32_le();
30602 __struct.ve = buf.get_f32_le();
30603 __struct.vd = buf.get_f32_le();
30604 __struct.speed_accuracy = buf.get_f32_le();
30605 __struct.horiz_accuracy = buf.get_f32_le();
30606 __struct.vert_accuracy = buf.get_f32_le();
30607 let tmp = buf.get_u16_le();
30608 __struct.ignore_flags = GpsInputIgnoreFlags::from_bits(
30609 tmp & GpsInputIgnoreFlags::all().bits(),
30610 )
30611 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
30612 flag_type: "GpsInputIgnoreFlags",
30613 value: tmp as u32,
30614 })?;
30615 __struct.time_week = buf.get_u16_le();
30616 __struct.gps_id = buf.get_u8();
30617 __struct.fix_type = buf.get_u8();
30618 __struct.satellites_visible = buf.get_u8();
30619 __struct.yaw = buf.get_u16_le();
30620 Ok(__struct)
30621 }
30622 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30623 let mut __tmp = BytesMut::new(bytes);
30624 #[allow(clippy::absurd_extreme_comparisons)]
30625 #[allow(unused_comparisons)]
30626 if __tmp.remaining() < Self::ENCODED_LEN {
30627 panic!(
30628 "buffer is too small (need {} bytes, but got {})",
30629 Self::ENCODED_LEN,
30630 __tmp.remaining(),
30631 )
30632 }
30633 __tmp.put_u64_le(self.time_usec);
30634 __tmp.put_u32_le(self.time_week_ms);
30635 __tmp.put_i32_le(self.lat);
30636 __tmp.put_i32_le(self.lon);
30637 __tmp.put_f32_le(self.alt);
30638 __tmp.put_f32_le(self.hdop);
30639 __tmp.put_f32_le(self.vdop);
30640 __tmp.put_f32_le(self.vn);
30641 __tmp.put_f32_le(self.ve);
30642 __tmp.put_f32_le(self.vd);
30643 __tmp.put_f32_le(self.speed_accuracy);
30644 __tmp.put_f32_le(self.horiz_accuracy);
30645 __tmp.put_f32_le(self.vert_accuracy);
30646 __tmp.put_u16_le(self.ignore_flags.bits());
30647 __tmp.put_u16_le(self.time_week);
30648 __tmp.put_u8(self.gps_id);
30649 __tmp.put_u8(self.fix_type);
30650 __tmp.put_u8(self.satellites_visible);
30651 __tmp.put_u16_le(self.yaw);
30652 if matches!(version, MavlinkVersion::V2) {
30653 let len = __tmp.len();
30654 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30655 } else {
30656 __tmp.len()
30657 }
30658 }
30659}
30660#[doc = "id: 11"]
30661#[doc = "Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component."]
30662#[derive(Debug, Clone, PartialEq)]
30663#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30664#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30665pub struct SET_MODE_DATA {
30666 #[doc = "The new autopilot-specific mode. This field can be ignored by an autopilot."]
30667 pub custom_mode: u32,
30668 #[doc = "The system setting the mode"]
30669 pub target_system: u8,
30670 #[doc = "The new base mode."]
30671 pub base_mode: MavMode,
30672}
30673impl SET_MODE_DATA {
30674 pub const ENCODED_LEN: usize = 6usize;
30675 pub const DEFAULT: Self = Self {
30676 custom_mode: 0_u32,
30677 target_system: 0_u8,
30678 base_mode: MavMode::DEFAULT,
30679 };
30680 #[cfg(feature = "arbitrary")]
30681 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30682 use arbitrary::{Arbitrary, Unstructured};
30683 let mut buf = [0u8; 1024];
30684 rng.fill_bytes(&mut buf);
30685 let mut unstructured = Unstructured::new(&buf);
30686 Self::arbitrary(&mut unstructured).unwrap_or_default()
30687 }
30688}
30689impl Default for SET_MODE_DATA {
30690 fn default() -> Self {
30691 Self::DEFAULT.clone()
30692 }
30693}
30694impl MessageData for SET_MODE_DATA {
30695 type Message = MavMessage;
30696 const ID: u32 = 11u32;
30697 const NAME: &'static str = "SET_MODE";
30698 const EXTRA_CRC: u8 = 89u8;
30699 const ENCODED_LEN: usize = 6usize;
30700 fn deser(
30701 _version: MavlinkVersion,
30702 __input: &[u8],
30703 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30704 let avail_len = __input.len();
30705 let mut payload_buf = [0; Self::ENCODED_LEN];
30706 let mut buf = if avail_len < Self::ENCODED_LEN {
30707 payload_buf[0..avail_len].copy_from_slice(__input);
30708 Bytes::new(&payload_buf)
30709 } else {
30710 Bytes::new(__input)
30711 };
30712 let mut __struct = Self::default();
30713 __struct.custom_mode = buf.get_u32_le();
30714 __struct.target_system = buf.get_u8();
30715 let tmp = buf.get_u8();
30716 __struct.base_mode =
30717 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30718 enum_type: "MavMode",
30719 value: tmp as u32,
30720 })?;
30721 Ok(__struct)
30722 }
30723 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30724 let mut __tmp = BytesMut::new(bytes);
30725 #[allow(clippy::absurd_extreme_comparisons)]
30726 #[allow(unused_comparisons)]
30727 if __tmp.remaining() < Self::ENCODED_LEN {
30728 panic!(
30729 "buffer is too small (need {} bytes, but got {})",
30730 Self::ENCODED_LEN,
30731 __tmp.remaining(),
30732 )
30733 }
30734 __tmp.put_u32_le(self.custom_mode);
30735 __tmp.put_u8(self.target_system);
30736 __tmp.put_u8(self.base_mode as u8);
30737 if matches!(version, MavlinkVersion::V2) {
30738 let len = __tmp.len();
30739 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30740 } else {
30741 __tmp.len()
30742 }
30743 }
30744}
30745#[doc = "id: 301"]
30746#[doc = "The location and information of an AIS vessel."]
30747#[derive(Debug, Clone, PartialEq)]
30748#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30749#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30750pub struct AIS_VESSEL_DATA {
30751 #[doc = "Mobile Marine Service Identifier, 9 decimal digits"]
30752 pub MMSI: u32,
30753 #[doc = "Latitude"]
30754 pub lat: i32,
30755 #[doc = "Longitude"]
30756 pub lon: i32,
30757 #[doc = "Course over ground"]
30758 pub COG: u16,
30759 #[doc = "True heading"]
30760 pub heading: u16,
30761 #[doc = "Speed over ground"]
30762 pub velocity: u16,
30763 #[doc = "Distance from lat/lon location to bow"]
30764 pub dimension_bow: u16,
30765 #[doc = "Distance from lat/lon location to stern"]
30766 pub dimension_stern: u16,
30767 #[doc = "Time since last communication in seconds"]
30768 pub tslc: u16,
30769 #[doc = "Bitmask to indicate various statuses including valid data fields"]
30770 pub flags: AisFlags,
30771 #[doc = "Turn rate"]
30772 pub turn_rate: i8,
30773 #[doc = "Navigational status"]
30774 pub navigational_status: AisNavStatus,
30775 #[doc = "Type of vessels"]
30776 pub mavtype: AisType,
30777 #[doc = "Distance from lat/lon location to port side"]
30778 pub dimension_port: u8,
30779 #[doc = "Distance from lat/lon location to starboard side"]
30780 pub dimension_starboard: u8,
30781 #[doc = "The vessel callsign"]
30782 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30783 pub callsign: [u8; 7],
30784 #[doc = "The vessel name"]
30785 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30786 pub name: [u8; 20],
30787}
30788impl AIS_VESSEL_DATA {
30789 pub const ENCODED_LEN: usize = 58usize;
30790 pub const DEFAULT: Self = Self {
30791 MMSI: 0_u32,
30792 lat: 0_i32,
30793 lon: 0_i32,
30794 COG: 0_u16,
30795 heading: 0_u16,
30796 velocity: 0_u16,
30797 dimension_bow: 0_u16,
30798 dimension_stern: 0_u16,
30799 tslc: 0_u16,
30800 flags: AisFlags::DEFAULT,
30801 turn_rate: 0_i8,
30802 navigational_status: AisNavStatus::DEFAULT,
30803 mavtype: AisType::DEFAULT,
30804 dimension_port: 0_u8,
30805 dimension_starboard: 0_u8,
30806 callsign: [0_u8; 7usize],
30807 name: [0_u8; 20usize],
30808 };
30809 #[cfg(feature = "arbitrary")]
30810 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30811 use arbitrary::{Arbitrary, Unstructured};
30812 let mut buf = [0u8; 1024];
30813 rng.fill_bytes(&mut buf);
30814 let mut unstructured = Unstructured::new(&buf);
30815 Self::arbitrary(&mut unstructured).unwrap_or_default()
30816 }
30817}
30818impl Default for AIS_VESSEL_DATA {
30819 fn default() -> Self {
30820 Self::DEFAULT.clone()
30821 }
30822}
30823impl MessageData for AIS_VESSEL_DATA {
30824 type Message = MavMessage;
30825 const ID: u32 = 301u32;
30826 const NAME: &'static str = "AIS_VESSEL";
30827 const EXTRA_CRC: u8 = 243u8;
30828 const ENCODED_LEN: usize = 58usize;
30829 fn deser(
30830 _version: MavlinkVersion,
30831 __input: &[u8],
30832 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30833 let avail_len = __input.len();
30834 let mut payload_buf = [0; Self::ENCODED_LEN];
30835 let mut buf = if avail_len < Self::ENCODED_LEN {
30836 payload_buf[0..avail_len].copy_from_slice(__input);
30837 Bytes::new(&payload_buf)
30838 } else {
30839 Bytes::new(__input)
30840 };
30841 let mut __struct = Self::default();
30842 __struct.MMSI = buf.get_u32_le();
30843 __struct.lat = buf.get_i32_le();
30844 __struct.lon = buf.get_i32_le();
30845 __struct.COG = buf.get_u16_le();
30846 __struct.heading = buf.get_u16_le();
30847 __struct.velocity = buf.get_u16_le();
30848 __struct.dimension_bow = buf.get_u16_le();
30849 __struct.dimension_stern = buf.get_u16_le();
30850 __struct.tslc = buf.get_u16_le();
30851 let tmp = buf.get_u16_le();
30852 __struct.flags = AisFlags::from_bits(tmp & AisFlags::all().bits()).ok_or(
30853 ::mavlink_core::error::ParserError::InvalidFlag {
30854 flag_type: "AisFlags",
30855 value: tmp as u32,
30856 },
30857 )?;
30858 __struct.turn_rate = buf.get_i8();
30859 let tmp = buf.get_u8();
30860 __struct.navigational_status =
30861 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30862 enum_type: "AisNavStatus",
30863 value: tmp as u32,
30864 })?;
30865 let tmp = buf.get_u8();
30866 __struct.mavtype =
30867 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
30868 enum_type: "AisType",
30869 value: tmp as u32,
30870 })?;
30871 __struct.dimension_port = buf.get_u8();
30872 __struct.dimension_starboard = buf.get_u8();
30873 for v in &mut __struct.callsign {
30874 let val = buf.get_u8();
30875 *v = val;
30876 }
30877 for v in &mut __struct.name {
30878 let val = buf.get_u8();
30879 *v = val;
30880 }
30881 Ok(__struct)
30882 }
30883 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
30884 let mut __tmp = BytesMut::new(bytes);
30885 #[allow(clippy::absurd_extreme_comparisons)]
30886 #[allow(unused_comparisons)]
30887 if __tmp.remaining() < Self::ENCODED_LEN {
30888 panic!(
30889 "buffer is too small (need {} bytes, but got {})",
30890 Self::ENCODED_LEN,
30891 __tmp.remaining(),
30892 )
30893 }
30894 __tmp.put_u32_le(self.MMSI);
30895 __tmp.put_i32_le(self.lat);
30896 __tmp.put_i32_le(self.lon);
30897 __tmp.put_u16_le(self.COG);
30898 __tmp.put_u16_le(self.heading);
30899 __tmp.put_u16_le(self.velocity);
30900 __tmp.put_u16_le(self.dimension_bow);
30901 __tmp.put_u16_le(self.dimension_stern);
30902 __tmp.put_u16_le(self.tslc);
30903 __tmp.put_u16_le(self.flags.bits());
30904 __tmp.put_i8(self.turn_rate);
30905 __tmp.put_u8(self.navigational_status as u8);
30906 __tmp.put_u8(self.mavtype as u8);
30907 __tmp.put_u8(self.dimension_port);
30908 __tmp.put_u8(self.dimension_starboard);
30909 for val in &self.callsign {
30910 __tmp.put_u8(*val);
30911 }
30912 for val in &self.name {
30913 __tmp.put_u8(*val);
30914 }
30915 if matches!(version, MavlinkVersion::V2) {
30916 let len = __tmp.len();
30917 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
30918 } else {
30919 __tmp.len()
30920 }
30921 }
30922}
30923#[doc = "id: 31"]
30924#[doc = "The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion. Quaternion order is w, x, y, z and a zero rotation would be expressed as (1 0 0 0)."]
30925#[derive(Debug, Clone, PartialEq)]
30926#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
30927#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
30928pub struct ATTITUDE_QUATERNION_DATA {
30929 #[doc = "Timestamp (time since system boot)."]
30930 pub time_boot_ms: u32,
30931 #[doc = "Quaternion component 1, w (1 in null-rotation)"]
30932 pub q1: f32,
30933 #[doc = "Quaternion component 2, x (0 in null-rotation)"]
30934 pub q2: f32,
30935 #[doc = "Quaternion component 3, y (0 in null-rotation)"]
30936 pub q3: f32,
30937 #[doc = "Quaternion component 4, z (0 in null-rotation)"]
30938 pub q4: f32,
30939 #[doc = "Roll angular speed"]
30940 pub rollspeed: f32,
30941 #[doc = "Pitch angular speed"]
30942 pub pitchspeed: f32,
30943 #[doc = "Yaw angular speed"]
30944 pub yawspeed: f32,
30945 #[doc = "Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode."]
30946 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
30947 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
30948 pub repr_offset_q: [f32; 4],
30949}
30950impl ATTITUDE_QUATERNION_DATA {
30951 pub const ENCODED_LEN: usize = 48usize;
30952 pub const DEFAULT: Self = Self {
30953 time_boot_ms: 0_u32,
30954 q1: 0.0_f32,
30955 q2: 0.0_f32,
30956 q3: 0.0_f32,
30957 q4: 0.0_f32,
30958 rollspeed: 0.0_f32,
30959 pitchspeed: 0.0_f32,
30960 yawspeed: 0.0_f32,
30961 repr_offset_q: [0.0_f32; 4usize],
30962 };
30963 #[cfg(feature = "arbitrary")]
30964 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
30965 use arbitrary::{Arbitrary, Unstructured};
30966 let mut buf = [0u8; 1024];
30967 rng.fill_bytes(&mut buf);
30968 let mut unstructured = Unstructured::new(&buf);
30969 Self::arbitrary(&mut unstructured).unwrap_or_default()
30970 }
30971}
30972impl Default for ATTITUDE_QUATERNION_DATA {
30973 fn default() -> Self {
30974 Self::DEFAULT.clone()
30975 }
30976}
30977impl MessageData for ATTITUDE_QUATERNION_DATA {
30978 type Message = MavMessage;
30979 const ID: u32 = 31u32;
30980 const NAME: &'static str = "ATTITUDE_QUATERNION";
30981 const EXTRA_CRC: u8 = 246u8;
30982 const ENCODED_LEN: usize = 48usize;
30983 fn deser(
30984 _version: MavlinkVersion,
30985 __input: &[u8],
30986 ) -> Result<Self, ::mavlink_core::error::ParserError> {
30987 let avail_len = __input.len();
30988 let mut payload_buf = [0; Self::ENCODED_LEN];
30989 let mut buf = if avail_len < Self::ENCODED_LEN {
30990 payload_buf[0..avail_len].copy_from_slice(__input);
30991 Bytes::new(&payload_buf)
30992 } else {
30993 Bytes::new(__input)
30994 };
30995 let mut __struct = Self::default();
30996 __struct.time_boot_ms = buf.get_u32_le();
30997 __struct.q1 = buf.get_f32_le();
30998 __struct.q2 = buf.get_f32_le();
30999 __struct.q3 = buf.get_f32_le();
31000 __struct.q4 = buf.get_f32_le();
31001 __struct.rollspeed = buf.get_f32_le();
31002 __struct.pitchspeed = buf.get_f32_le();
31003 __struct.yawspeed = buf.get_f32_le();
31004 for v in &mut __struct.repr_offset_q {
31005 let val = buf.get_f32_le();
31006 *v = val;
31007 }
31008 Ok(__struct)
31009 }
31010 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31011 let mut __tmp = BytesMut::new(bytes);
31012 #[allow(clippy::absurd_extreme_comparisons)]
31013 #[allow(unused_comparisons)]
31014 if __tmp.remaining() < Self::ENCODED_LEN {
31015 panic!(
31016 "buffer is too small (need {} bytes, but got {})",
31017 Self::ENCODED_LEN,
31018 __tmp.remaining(),
31019 )
31020 }
31021 __tmp.put_u32_le(self.time_boot_ms);
31022 __tmp.put_f32_le(self.q1);
31023 __tmp.put_f32_le(self.q2);
31024 __tmp.put_f32_le(self.q3);
31025 __tmp.put_f32_le(self.q4);
31026 __tmp.put_f32_le(self.rollspeed);
31027 __tmp.put_f32_le(self.pitchspeed);
31028 __tmp.put_f32_le(self.yawspeed);
31029 for val in &self.repr_offset_q {
31030 __tmp.put_f32_le(*val);
31031 }
31032 if matches!(version, MavlinkVersion::V2) {
31033 let len = __tmp.len();
31034 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31035 } else {
31036 __tmp.len()
31037 }
31038 }
31039}
31040#[doc = "id: 436"]
31041#[doc = "Get the current mode. This should be emitted on any mode change, and broadcast at low rate (nominally 0.5 Hz). It may be requested using MAV_CMD_REQUEST_MESSAGE. See <https://mavlink.io/en/services/standard_modes.html>."]
31042#[derive(Debug, Clone, PartialEq)]
31043#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31044#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31045pub struct CURRENT_MODE_DATA {
31046 #[doc = "A bitfield for use for autopilot-specific flags"]
31047 pub custom_mode: u32,
31048 #[doc = "The custom_mode of the mode that was last commanded by the user (for example, with MAV_CMD_DO_SET_STANDARD_MODE, MAV_CMD_DO_SET_MODE or via RC). This should usually be the same as custom_mode. It will be different if the vehicle is unable to enter the intended mode, or has left that mode due to a failsafe condition. 0 indicates the intended custom mode is unknown/not supplied"]
31049 pub intended_custom_mode: u32,
31050 #[doc = "Standard mode."]
31051 pub standard_mode: MavStandardMode,
31052}
31053impl CURRENT_MODE_DATA {
31054 pub const ENCODED_LEN: usize = 9usize;
31055 pub const DEFAULT: Self = Self {
31056 custom_mode: 0_u32,
31057 intended_custom_mode: 0_u32,
31058 standard_mode: MavStandardMode::DEFAULT,
31059 };
31060 #[cfg(feature = "arbitrary")]
31061 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31062 use arbitrary::{Arbitrary, Unstructured};
31063 let mut buf = [0u8; 1024];
31064 rng.fill_bytes(&mut buf);
31065 let mut unstructured = Unstructured::new(&buf);
31066 Self::arbitrary(&mut unstructured).unwrap_or_default()
31067 }
31068}
31069impl Default for CURRENT_MODE_DATA {
31070 fn default() -> Self {
31071 Self::DEFAULT.clone()
31072 }
31073}
31074impl MessageData for CURRENT_MODE_DATA {
31075 type Message = MavMessage;
31076 const ID: u32 = 436u32;
31077 const NAME: &'static str = "CURRENT_MODE";
31078 const EXTRA_CRC: u8 = 193u8;
31079 const ENCODED_LEN: usize = 9usize;
31080 fn deser(
31081 _version: MavlinkVersion,
31082 __input: &[u8],
31083 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31084 let avail_len = __input.len();
31085 let mut payload_buf = [0; Self::ENCODED_LEN];
31086 let mut buf = if avail_len < Self::ENCODED_LEN {
31087 payload_buf[0..avail_len].copy_from_slice(__input);
31088 Bytes::new(&payload_buf)
31089 } else {
31090 Bytes::new(__input)
31091 };
31092 let mut __struct = Self::default();
31093 __struct.custom_mode = buf.get_u32_le();
31094 __struct.intended_custom_mode = buf.get_u32_le();
31095 let tmp = buf.get_u8();
31096 __struct.standard_mode =
31097 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31098 enum_type: "MavStandardMode",
31099 value: tmp as u32,
31100 })?;
31101 Ok(__struct)
31102 }
31103 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31104 let mut __tmp = BytesMut::new(bytes);
31105 #[allow(clippy::absurd_extreme_comparisons)]
31106 #[allow(unused_comparisons)]
31107 if __tmp.remaining() < Self::ENCODED_LEN {
31108 panic!(
31109 "buffer is too small (need {} bytes, but got {})",
31110 Self::ENCODED_LEN,
31111 __tmp.remaining(),
31112 )
31113 }
31114 __tmp.put_u32_le(self.custom_mode);
31115 __tmp.put_u32_le(self.intended_custom_mode);
31116 __tmp.put_u8(self.standard_mode as u8);
31117 if matches!(version, MavlinkVersion::V2) {
31118 let len = __tmp.len();
31119 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31120 } else {
31121 __tmp.len()
31122 }
31123 }
31124}
31125#[doc = "id: 284"]
31126#[doc = "Low level message to control a gimbal device's attitude. \t This message is to be sent from the gimbal manager to the gimbal device component. \t The quaternion and angular velocities can be set to NaN according to use case. \t For the angles encoded in the quaternion and the angular velocities holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME is set, then they are relative to the vehicle heading (vehicle frame). \t If the flag GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is set, then they are relative to absolute North (earth frame). \t If neither of these flags are set, then (for backwards compatibility) it holds: \t If the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, then they are relative to absolute North (earth frame), \t else they are relative to the vehicle heading (vehicle frame). \t Setting both GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME and GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME is not allowed. \t These rules are to ensure backwards compatibility. \t New implementations should always set either GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME or GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME."]
31127#[derive(Debug, Clone, PartialEq)]
31128#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31129#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31130pub struct GIMBAL_DEVICE_SET_ATTITUDE_DATA {
31131 #[doc = "Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation). The frame is described in the message description. Set fields to NaN to be ignored."]
31132 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31133 pub q: [f32; 4],
31134 #[doc = "X component of angular velocity (positive: rolling to the right). The frame is described in the message description. NaN to be ignored."]
31135 pub angular_velocity_x: f32,
31136 #[doc = "Y component of angular velocity (positive: pitching up). The frame is described in the message description. NaN to be ignored."]
31137 pub angular_velocity_y: f32,
31138 #[doc = "Z component of angular velocity (positive: yawing to the right). The frame is described in the message description. NaN to be ignored."]
31139 pub angular_velocity_z: f32,
31140 #[doc = "Low level gimbal flags."]
31141 pub flags: GimbalDeviceFlags,
31142 #[doc = "System ID"]
31143 pub target_system: u8,
31144 #[doc = "Component ID"]
31145 pub target_component: u8,
31146}
31147impl GIMBAL_DEVICE_SET_ATTITUDE_DATA {
31148 pub const ENCODED_LEN: usize = 32usize;
31149 pub const DEFAULT: Self = Self {
31150 q: [0.0_f32; 4usize],
31151 angular_velocity_x: 0.0_f32,
31152 angular_velocity_y: 0.0_f32,
31153 angular_velocity_z: 0.0_f32,
31154 flags: GimbalDeviceFlags::DEFAULT,
31155 target_system: 0_u8,
31156 target_component: 0_u8,
31157 };
31158 #[cfg(feature = "arbitrary")]
31159 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31160 use arbitrary::{Arbitrary, Unstructured};
31161 let mut buf = [0u8; 1024];
31162 rng.fill_bytes(&mut buf);
31163 let mut unstructured = Unstructured::new(&buf);
31164 Self::arbitrary(&mut unstructured).unwrap_or_default()
31165 }
31166}
31167impl Default for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
31168 fn default() -> Self {
31169 Self::DEFAULT.clone()
31170 }
31171}
31172impl MessageData for GIMBAL_DEVICE_SET_ATTITUDE_DATA {
31173 type Message = MavMessage;
31174 const ID: u32 = 284u32;
31175 const NAME: &'static str = "GIMBAL_DEVICE_SET_ATTITUDE";
31176 const EXTRA_CRC: u8 = 99u8;
31177 const ENCODED_LEN: usize = 32usize;
31178 fn deser(
31179 _version: MavlinkVersion,
31180 __input: &[u8],
31181 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31182 let avail_len = __input.len();
31183 let mut payload_buf = [0; Self::ENCODED_LEN];
31184 let mut buf = if avail_len < Self::ENCODED_LEN {
31185 payload_buf[0..avail_len].copy_from_slice(__input);
31186 Bytes::new(&payload_buf)
31187 } else {
31188 Bytes::new(__input)
31189 };
31190 let mut __struct = Self::default();
31191 for v in &mut __struct.q {
31192 let val = buf.get_f32_le();
31193 *v = val;
31194 }
31195 __struct.angular_velocity_x = buf.get_f32_le();
31196 __struct.angular_velocity_y = buf.get_f32_le();
31197 __struct.angular_velocity_z = buf.get_f32_le();
31198 let tmp = buf.get_u16_le();
31199 __struct.flags = GimbalDeviceFlags::from_bits(tmp & GimbalDeviceFlags::all().bits())
31200 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31201 flag_type: "GimbalDeviceFlags",
31202 value: tmp as u32,
31203 })?;
31204 __struct.target_system = buf.get_u8();
31205 __struct.target_component = buf.get_u8();
31206 Ok(__struct)
31207 }
31208 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31209 let mut __tmp = BytesMut::new(bytes);
31210 #[allow(clippy::absurd_extreme_comparisons)]
31211 #[allow(unused_comparisons)]
31212 if __tmp.remaining() < Self::ENCODED_LEN {
31213 panic!(
31214 "buffer is too small (need {} bytes, but got {})",
31215 Self::ENCODED_LEN,
31216 __tmp.remaining(),
31217 )
31218 }
31219 for val in &self.q {
31220 __tmp.put_f32_le(*val);
31221 }
31222 __tmp.put_f32_le(self.angular_velocity_x);
31223 __tmp.put_f32_le(self.angular_velocity_y);
31224 __tmp.put_f32_le(self.angular_velocity_z);
31225 __tmp.put_u16_le(self.flags.bits());
31226 __tmp.put_u8(self.target_system);
31227 __tmp.put_u8(self.target_component);
31228 if matches!(version, MavlinkVersion::V2) {
31229 let len = __tmp.len();
31230 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31231 } else {
31232 __tmp.len()
31233 }
31234 }
31235}
31236#[doc = "id: 12920"]
31237#[doc = "Temperature and humidity from hygrometer."]
31238#[derive(Debug, Clone, PartialEq)]
31239#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31240#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31241pub struct HYGROMETER_SENSOR_DATA {
31242 #[doc = "Temperature"]
31243 pub temperature: i16,
31244 #[doc = "Humidity"]
31245 pub humidity: u16,
31246 #[doc = "Hygrometer ID"]
31247 pub id: u8,
31248}
31249impl HYGROMETER_SENSOR_DATA {
31250 pub const ENCODED_LEN: usize = 5usize;
31251 pub const DEFAULT: Self = Self {
31252 temperature: 0_i16,
31253 humidity: 0_u16,
31254 id: 0_u8,
31255 };
31256 #[cfg(feature = "arbitrary")]
31257 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31258 use arbitrary::{Arbitrary, Unstructured};
31259 let mut buf = [0u8; 1024];
31260 rng.fill_bytes(&mut buf);
31261 let mut unstructured = Unstructured::new(&buf);
31262 Self::arbitrary(&mut unstructured).unwrap_or_default()
31263 }
31264}
31265impl Default for HYGROMETER_SENSOR_DATA {
31266 fn default() -> Self {
31267 Self::DEFAULT.clone()
31268 }
31269}
31270impl MessageData for HYGROMETER_SENSOR_DATA {
31271 type Message = MavMessage;
31272 const ID: u32 = 12920u32;
31273 const NAME: &'static str = "HYGROMETER_SENSOR";
31274 const EXTRA_CRC: u8 = 20u8;
31275 const ENCODED_LEN: usize = 5usize;
31276 fn deser(
31277 _version: MavlinkVersion,
31278 __input: &[u8],
31279 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31280 let avail_len = __input.len();
31281 let mut payload_buf = [0; Self::ENCODED_LEN];
31282 let mut buf = if avail_len < Self::ENCODED_LEN {
31283 payload_buf[0..avail_len].copy_from_slice(__input);
31284 Bytes::new(&payload_buf)
31285 } else {
31286 Bytes::new(__input)
31287 };
31288 let mut __struct = Self::default();
31289 __struct.temperature = buf.get_i16_le();
31290 __struct.humidity = buf.get_u16_le();
31291 __struct.id = buf.get_u8();
31292 Ok(__struct)
31293 }
31294 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31295 let mut __tmp = BytesMut::new(bytes);
31296 #[allow(clippy::absurd_extreme_comparisons)]
31297 #[allow(unused_comparisons)]
31298 if __tmp.remaining() < Self::ENCODED_LEN {
31299 panic!(
31300 "buffer is too small (need {} bytes, but got {})",
31301 Self::ENCODED_LEN,
31302 __tmp.remaining(),
31303 )
31304 }
31305 __tmp.put_i16_le(self.temperature);
31306 __tmp.put_u16_le(self.humidity);
31307 __tmp.put_u8(self.id);
31308 if matches!(version, MavlinkVersion::V2) {
31309 let len = __tmp.len();
31310 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31311 } else {
31312 __tmp.len()
31313 }
31314 }
31315}
31316#[doc = "id: 50"]
31317#[doc = "Bind a RC channel to a parameter. The parameter should change according to the RC channel value."]
31318#[derive(Debug, Clone, PartialEq)]
31319#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31320#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31321pub struct PARAM_MAP_RC_DATA {
31322 #[doc = "Initial parameter value"]
31323 pub param_value0: f32,
31324 #[doc = "Scale, maps the RC range [-1, 1] to a parameter value"]
31325 pub scale: f32,
31326 #[doc = "Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)"]
31327 pub param_value_min: f32,
31328 #[doc = "Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)"]
31329 pub param_value_max: f32,
31330 #[doc = "Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index."]
31331 pub param_index: i16,
31332 #[doc = "System ID"]
31333 pub target_system: u8,
31334 #[doc = "Component ID"]
31335 pub target_component: u8,
31336 #[doc = "Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string"]
31337 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31338 pub param_id: [u8; 16],
31339 #[doc = "Index of parameter RC channel. Not equal to the RC channel id. Typically corresponds to a potentiometer-knob on the RC."]
31340 pub parameter_rc_channel_index: u8,
31341}
31342impl PARAM_MAP_RC_DATA {
31343 pub const ENCODED_LEN: usize = 37usize;
31344 pub const DEFAULT: Self = Self {
31345 param_value0: 0.0_f32,
31346 scale: 0.0_f32,
31347 param_value_min: 0.0_f32,
31348 param_value_max: 0.0_f32,
31349 param_index: 0_i16,
31350 target_system: 0_u8,
31351 target_component: 0_u8,
31352 param_id: [0_u8; 16usize],
31353 parameter_rc_channel_index: 0_u8,
31354 };
31355 #[cfg(feature = "arbitrary")]
31356 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31357 use arbitrary::{Arbitrary, Unstructured};
31358 let mut buf = [0u8; 1024];
31359 rng.fill_bytes(&mut buf);
31360 let mut unstructured = Unstructured::new(&buf);
31361 Self::arbitrary(&mut unstructured).unwrap_or_default()
31362 }
31363}
31364impl Default for PARAM_MAP_RC_DATA {
31365 fn default() -> Self {
31366 Self::DEFAULT.clone()
31367 }
31368}
31369impl MessageData for PARAM_MAP_RC_DATA {
31370 type Message = MavMessage;
31371 const ID: u32 = 50u32;
31372 const NAME: &'static str = "PARAM_MAP_RC";
31373 const EXTRA_CRC: u8 = 78u8;
31374 const ENCODED_LEN: usize = 37usize;
31375 fn deser(
31376 _version: MavlinkVersion,
31377 __input: &[u8],
31378 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31379 let avail_len = __input.len();
31380 let mut payload_buf = [0; Self::ENCODED_LEN];
31381 let mut buf = if avail_len < Self::ENCODED_LEN {
31382 payload_buf[0..avail_len].copy_from_slice(__input);
31383 Bytes::new(&payload_buf)
31384 } else {
31385 Bytes::new(__input)
31386 };
31387 let mut __struct = Self::default();
31388 __struct.param_value0 = buf.get_f32_le();
31389 __struct.scale = buf.get_f32_le();
31390 __struct.param_value_min = buf.get_f32_le();
31391 __struct.param_value_max = buf.get_f32_le();
31392 __struct.param_index = buf.get_i16_le();
31393 __struct.target_system = buf.get_u8();
31394 __struct.target_component = buf.get_u8();
31395 for v in &mut __struct.param_id {
31396 let val = buf.get_u8();
31397 *v = val;
31398 }
31399 __struct.parameter_rc_channel_index = buf.get_u8();
31400 Ok(__struct)
31401 }
31402 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31403 let mut __tmp = BytesMut::new(bytes);
31404 #[allow(clippy::absurd_extreme_comparisons)]
31405 #[allow(unused_comparisons)]
31406 if __tmp.remaining() < Self::ENCODED_LEN {
31407 panic!(
31408 "buffer is too small (need {} bytes, but got {})",
31409 Self::ENCODED_LEN,
31410 __tmp.remaining(),
31411 )
31412 }
31413 __tmp.put_f32_le(self.param_value0);
31414 __tmp.put_f32_le(self.scale);
31415 __tmp.put_f32_le(self.param_value_min);
31416 __tmp.put_f32_le(self.param_value_max);
31417 __tmp.put_i16_le(self.param_index);
31418 __tmp.put_u8(self.target_system);
31419 __tmp.put_u8(self.target_component);
31420 for val in &self.param_id {
31421 __tmp.put_u8(*val);
31422 }
31423 __tmp.put_u8(self.parameter_rc_channel_index);
31424 if matches!(version, MavlinkVersion::V2) {
31425 let len = __tmp.len();
31426 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31427 } else {
31428 __tmp.len()
31429 }
31430 }
31431}
31432#[doc = "id: 396"]
31433#[doc = "Basic component information data. Should be requested using MAV_CMD_REQUEST_MESSAGE on startup, or when required."]
31434#[derive(Debug, Clone, PartialEq)]
31435#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31436#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31437pub struct COMPONENT_INFORMATION_BASIC_DATA {
31438 #[doc = "Component capability flags"]
31439 pub capabilities: MavProtocolCapability,
31440 #[doc = "Timestamp (time since system boot)."]
31441 pub time_boot_ms: u32,
31442 #[doc = "Date of manufacture as a UNIX Epoch time (since 1.1.1970) in seconds."]
31443 pub time_manufacture_s: u32,
31444 #[doc = "Name of the component vendor. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
31445 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31446 pub vendor_name: [u8; 32],
31447 #[doc = "Name of the component model. Needs to be zero terminated. The field is optional and can be empty/all zeros."]
31448 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31449 pub model_name: [u8; 32],
31450 #[doc = "Software version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
31451 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31452 pub software_version: [u8; 24],
31453 #[doc = "Hardware version. The recommended format is SEMVER: 'major.minor.patch' (any format may be used). The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
31454 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31455 pub hardware_version: [u8; 24],
31456 #[doc = "Hardware serial number. The field must be zero terminated if it has a value. The field is optional and can be empty/all zeros."]
31457 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31458 pub serial_number: [u8; 32],
31459}
31460impl COMPONENT_INFORMATION_BASIC_DATA {
31461 pub const ENCODED_LEN: usize = 160usize;
31462 pub const DEFAULT: Self = Self {
31463 capabilities: MavProtocolCapability::DEFAULT,
31464 time_boot_ms: 0_u32,
31465 time_manufacture_s: 0_u32,
31466 vendor_name: [0_u8; 32usize],
31467 model_name: [0_u8; 32usize],
31468 software_version: [0_u8; 24usize],
31469 hardware_version: [0_u8; 24usize],
31470 serial_number: [0_u8; 32usize],
31471 };
31472 #[cfg(feature = "arbitrary")]
31473 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31474 use arbitrary::{Arbitrary, Unstructured};
31475 let mut buf = [0u8; 1024];
31476 rng.fill_bytes(&mut buf);
31477 let mut unstructured = Unstructured::new(&buf);
31478 Self::arbitrary(&mut unstructured).unwrap_or_default()
31479 }
31480}
31481impl Default for COMPONENT_INFORMATION_BASIC_DATA {
31482 fn default() -> Self {
31483 Self::DEFAULT.clone()
31484 }
31485}
31486impl MessageData for COMPONENT_INFORMATION_BASIC_DATA {
31487 type Message = MavMessage;
31488 const ID: u32 = 396u32;
31489 const NAME: &'static str = "COMPONENT_INFORMATION_BASIC";
31490 const EXTRA_CRC: u8 = 50u8;
31491 const ENCODED_LEN: usize = 160usize;
31492 fn deser(
31493 _version: MavlinkVersion,
31494 __input: &[u8],
31495 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31496 let avail_len = __input.len();
31497 let mut payload_buf = [0; Self::ENCODED_LEN];
31498 let mut buf = if avail_len < Self::ENCODED_LEN {
31499 payload_buf[0..avail_len].copy_from_slice(__input);
31500 Bytes::new(&payload_buf)
31501 } else {
31502 Bytes::new(__input)
31503 };
31504 let mut __struct = Self::default();
31505 let tmp = buf.get_u64_le();
31506 __struct.capabilities = MavProtocolCapability::from_bits(
31507 tmp & MavProtocolCapability::all().bits(),
31508 )
31509 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31510 flag_type: "MavProtocolCapability",
31511 value: tmp as u32,
31512 })?;
31513 __struct.time_boot_ms = buf.get_u32_le();
31514 __struct.time_manufacture_s = buf.get_u32_le();
31515 for v in &mut __struct.vendor_name {
31516 let val = buf.get_u8();
31517 *v = val;
31518 }
31519 for v in &mut __struct.model_name {
31520 let val = buf.get_u8();
31521 *v = val;
31522 }
31523 for v in &mut __struct.software_version {
31524 let val = buf.get_u8();
31525 *v = val;
31526 }
31527 for v in &mut __struct.hardware_version {
31528 let val = buf.get_u8();
31529 *v = val;
31530 }
31531 for v in &mut __struct.serial_number {
31532 let val = buf.get_u8();
31533 *v = val;
31534 }
31535 Ok(__struct)
31536 }
31537 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31538 let mut __tmp = BytesMut::new(bytes);
31539 #[allow(clippy::absurd_extreme_comparisons)]
31540 #[allow(unused_comparisons)]
31541 if __tmp.remaining() < Self::ENCODED_LEN {
31542 panic!(
31543 "buffer is too small (need {} bytes, but got {})",
31544 Self::ENCODED_LEN,
31545 __tmp.remaining(),
31546 )
31547 }
31548 __tmp.put_u64_le(self.capabilities.bits());
31549 __tmp.put_u32_le(self.time_boot_ms);
31550 __tmp.put_u32_le(self.time_manufacture_s);
31551 for val in &self.vendor_name {
31552 __tmp.put_u8(*val);
31553 }
31554 for val in &self.model_name {
31555 __tmp.put_u8(*val);
31556 }
31557 for val in &self.software_version {
31558 __tmp.put_u8(*val);
31559 }
31560 for val in &self.hardware_version {
31561 __tmp.put_u8(*val);
31562 }
31563 for val in &self.serial_number {
31564 __tmp.put_u8(*val);
31565 }
31566 if matches!(version, MavlinkVersion::V2) {
31567 let len = __tmp.len();
31568 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31569 } else {
31570 __tmp.len()
31571 }
31572 }
31573}
31574#[doc = "id: 12904"]
31575#[doc = "Data for filling the OpenDroneID System message. The System Message contains general system information including the operator location/altitude and possible aircraft group and/or category/class information."]
31576#[derive(Debug, Clone, PartialEq)]
31577#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31578#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31579pub struct OPEN_DRONE_ID_SYSTEM_DATA {
31580 #[doc = "Latitude of the operator. If unknown: 0 (both Lat/Lon)."]
31581 pub operator_latitude: i32,
31582 #[doc = "Longitude of the operator. If unknown: 0 (both Lat/Lon)."]
31583 pub operator_longitude: i32,
31584 #[doc = "Area Operations Ceiling relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
31585 pub area_ceiling: f32,
31586 #[doc = "Area Operations Floor relative to WGS84. If unknown: -1000 m. Used only for swarms/multiple UA."]
31587 pub area_floor: f32,
31588 #[doc = "Geodetic altitude of the operator relative to WGS84. If unknown: -1000 m."]
31589 pub operator_altitude_geo: f32,
31590 #[doc = "32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019."]
31591 pub timestamp: u32,
31592 #[doc = "Number of aircraft in the area, group or formation (default 1). Used only for swarms/multiple UA."]
31593 pub area_count: u16,
31594 #[doc = "Radius of the cylindrical area of the group or formation (default 0). Used only for swarms/multiple UA."]
31595 pub area_radius: u16,
31596 #[doc = "System ID (0 for broadcast)."]
31597 pub target_system: u8,
31598 #[doc = "Component ID (0 for broadcast)."]
31599 pub target_component: u8,
31600 #[doc = "Only used for drone ID data received from other UAs. See detailed description at <https://mavlink.io/en/services/opendroneid.html>."]
31601 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31602 pub id_or_mac: [u8; 20],
31603 #[doc = "Specifies the operator location type."]
31604 pub operator_location_type: MavOdidOperatorLocationType,
31605 #[doc = "Specifies the classification type of the UA."]
31606 pub classification_type: MavOdidClassificationType,
31607 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA."]
31608 pub category_eu: MavOdidCategoryEu,
31609 #[doc = "When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA."]
31610 pub class_eu: MavOdidClassEu,
31611}
31612impl OPEN_DRONE_ID_SYSTEM_DATA {
31613 pub const ENCODED_LEN: usize = 54usize;
31614 pub const DEFAULT: Self = Self {
31615 operator_latitude: 0_i32,
31616 operator_longitude: 0_i32,
31617 area_ceiling: 0.0_f32,
31618 area_floor: 0.0_f32,
31619 operator_altitude_geo: 0.0_f32,
31620 timestamp: 0_u32,
31621 area_count: 0_u16,
31622 area_radius: 0_u16,
31623 target_system: 0_u8,
31624 target_component: 0_u8,
31625 id_or_mac: [0_u8; 20usize],
31626 operator_location_type: MavOdidOperatorLocationType::DEFAULT,
31627 classification_type: MavOdidClassificationType::DEFAULT,
31628 category_eu: MavOdidCategoryEu::DEFAULT,
31629 class_eu: MavOdidClassEu::DEFAULT,
31630 };
31631 #[cfg(feature = "arbitrary")]
31632 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31633 use arbitrary::{Arbitrary, Unstructured};
31634 let mut buf = [0u8; 1024];
31635 rng.fill_bytes(&mut buf);
31636 let mut unstructured = Unstructured::new(&buf);
31637 Self::arbitrary(&mut unstructured).unwrap_or_default()
31638 }
31639}
31640impl Default for OPEN_DRONE_ID_SYSTEM_DATA {
31641 fn default() -> Self {
31642 Self::DEFAULT.clone()
31643 }
31644}
31645impl MessageData for OPEN_DRONE_ID_SYSTEM_DATA {
31646 type Message = MavMessage;
31647 const ID: u32 = 12904u32;
31648 const NAME: &'static str = "OPEN_DRONE_ID_SYSTEM";
31649 const EXTRA_CRC: u8 = 77u8;
31650 const ENCODED_LEN: usize = 54usize;
31651 fn deser(
31652 _version: MavlinkVersion,
31653 __input: &[u8],
31654 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31655 let avail_len = __input.len();
31656 let mut payload_buf = [0; Self::ENCODED_LEN];
31657 let mut buf = if avail_len < Self::ENCODED_LEN {
31658 payload_buf[0..avail_len].copy_from_slice(__input);
31659 Bytes::new(&payload_buf)
31660 } else {
31661 Bytes::new(__input)
31662 };
31663 let mut __struct = Self::default();
31664 __struct.operator_latitude = buf.get_i32_le();
31665 __struct.operator_longitude = buf.get_i32_le();
31666 __struct.area_ceiling = buf.get_f32_le();
31667 __struct.area_floor = buf.get_f32_le();
31668 __struct.operator_altitude_geo = buf.get_f32_le();
31669 __struct.timestamp = buf.get_u32_le();
31670 __struct.area_count = buf.get_u16_le();
31671 __struct.area_radius = buf.get_u16_le();
31672 __struct.target_system = buf.get_u8();
31673 __struct.target_component = buf.get_u8();
31674 for v in &mut __struct.id_or_mac {
31675 let val = buf.get_u8();
31676 *v = val;
31677 }
31678 let tmp = buf.get_u8();
31679 __struct.operator_location_type =
31680 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31681 enum_type: "MavOdidOperatorLocationType",
31682 value: tmp as u32,
31683 })?;
31684 let tmp = buf.get_u8();
31685 __struct.classification_type =
31686 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31687 enum_type: "MavOdidClassificationType",
31688 value: tmp as u32,
31689 })?;
31690 let tmp = buf.get_u8();
31691 __struct.category_eu =
31692 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31693 enum_type: "MavOdidCategoryEu",
31694 value: tmp as u32,
31695 })?;
31696 let tmp = buf.get_u8();
31697 __struct.class_eu =
31698 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31699 enum_type: "MavOdidClassEu",
31700 value: tmp as u32,
31701 })?;
31702 Ok(__struct)
31703 }
31704 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31705 let mut __tmp = BytesMut::new(bytes);
31706 #[allow(clippy::absurd_extreme_comparisons)]
31707 #[allow(unused_comparisons)]
31708 if __tmp.remaining() < Self::ENCODED_LEN {
31709 panic!(
31710 "buffer is too small (need {} bytes, but got {})",
31711 Self::ENCODED_LEN,
31712 __tmp.remaining(),
31713 )
31714 }
31715 __tmp.put_i32_le(self.operator_latitude);
31716 __tmp.put_i32_le(self.operator_longitude);
31717 __tmp.put_f32_le(self.area_ceiling);
31718 __tmp.put_f32_le(self.area_floor);
31719 __tmp.put_f32_le(self.operator_altitude_geo);
31720 __tmp.put_u32_le(self.timestamp);
31721 __tmp.put_u16_le(self.area_count);
31722 __tmp.put_u16_le(self.area_radius);
31723 __tmp.put_u8(self.target_system);
31724 __tmp.put_u8(self.target_component);
31725 for val in &self.id_or_mac {
31726 __tmp.put_u8(*val);
31727 }
31728 __tmp.put_u8(self.operator_location_type as u8);
31729 __tmp.put_u8(self.classification_type as u8);
31730 __tmp.put_u8(self.category_eu as u8);
31731 __tmp.put_u8(self.class_eu as u8);
31732 if matches!(version, MavlinkVersion::V2) {
31733 let len = __tmp.len();
31734 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31735 } else {
31736 __tmp.len()
31737 }
31738 }
31739}
31740#[doc = "id: 77"]
31741#[doc = "Report status of a command. Includes feedback whether the command was executed. The command microservice is documented at <https://mavlink.io/en/services/command.html>."]
31742#[derive(Debug, Clone, PartialEq)]
31743#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31744#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31745pub struct COMMAND_ACK_DATA {
31746 #[doc = "Command ID (of acknowledged command)."]
31747 pub command: MavCmd,
31748 #[doc = "Result of command."]
31749 pub result: MavResult,
31750 #[doc = "The progress percentage when result is MAV_RESULT_IN_PROGRESS. Values: [0-100], or UINT8_MAX if the progress is unknown."]
31751 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31752 pub progress: u8,
31753 #[doc = "Additional result information. Can be set with a command-specific enum containing command-specific error reasons for why the command might be denied. If used, the associated enum must be documented in the corresponding MAV_CMD (this enum should have a 0 value to indicate \"unused\" or \"unknown\")."]
31754 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31755 pub result_param2: i32,
31756 #[doc = "System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
31757 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31758 pub target_system: u8,
31759 #[doc = "Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement."]
31760 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31761 pub target_component: u8,
31762}
31763impl COMMAND_ACK_DATA {
31764 pub const ENCODED_LEN: usize = 10usize;
31765 pub const DEFAULT: Self = Self {
31766 command: MavCmd::DEFAULT,
31767 result: MavResult::DEFAULT,
31768 progress: 0_u8,
31769 result_param2: 0_i32,
31770 target_system: 0_u8,
31771 target_component: 0_u8,
31772 };
31773 #[cfg(feature = "arbitrary")]
31774 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31775 use arbitrary::{Arbitrary, Unstructured};
31776 let mut buf = [0u8; 1024];
31777 rng.fill_bytes(&mut buf);
31778 let mut unstructured = Unstructured::new(&buf);
31779 Self::arbitrary(&mut unstructured).unwrap_or_default()
31780 }
31781}
31782impl Default for COMMAND_ACK_DATA {
31783 fn default() -> Self {
31784 Self::DEFAULT.clone()
31785 }
31786}
31787impl MessageData for COMMAND_ACK_DATA {
31788 type Message = MavMessage;
31789 const ID: u32 = 77u32;
31790 const NAME: &'static str = "COMMAND_ACK";
31791 const EXTRA_CRC: u8 = 143u8;
31792 const ENCODED_LEN: usize = 10usize;
31793 fn deser(
31794 _version: MavlinkVersion,
31795 __input: &[u8],
31796 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31797 let avail_len = __input.len();
31798 let mut payload_buf = [0; Self::ENCODED_LEN];
31799 let mut buf = if avail_len < Self::ENCODED_LEN {
31800 payload_buf[0..avail_len].copy_from_slice(__input);
31801 Bytes::new(&payload_buf)
31802 } else {
31803 Bytes::new(__input)
31804 };
31805 let mut __struct = Self::default();
31806 let tmp = buf.get_u16_le();
31807 __struct.command = FromPrimitive::from_u16(tmp).ok_or(
31808 ::mavlink_core::error::ParserError::InvalidEnum {
31809 enum_type: "MavCmd",
31810 value: tmp as u32,
31811 },
31812 )?;
31813 let tmp = buf.get_u8();
31814 __struct.result =
31815 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31816 enum_type: "MavResult",
31817 value: tmp as u32,
31818 })?;
31819 __struct.progress = buf.get_u8();
31820 __struct.result_param2 = buf.get_i32_le();
31821 __struct.target_system = buf.get_u8();
31822 __struct.target_component = buf.get_u8();
31823 Ok(__struct)
31824 }
31825 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31826 let mut __tmp = BytesMut::new(bytes);
31827 #[allow(clippy::absurd_extreme_comparisons)]
31828 #[allow(unused_comparisons)]
31829 if __tmp.remaining() < Self::ENCODED_LEN {
31830 panic!(
31831 "buffer is too small (need {} bytes, but got {})",
31832 Self::ENCODED_LEN,
31833 __tmp.remaining(),
31834 )
31835 }
31836 __tmp.put_u16_le(self.command as u16);
31837 __tmp.put_u8(self.result as u8);
31838 __tmp.put_u8(self.progress);
31839 __tmp.put_i32_le(self.result_param2);
31840 __tmp.put_u8(self.target_system);
31841 __tmp.put_u8(self.target_component);
31842 if matches!(version, MavlinkVersion::V2) {
31843 let len = __tmp.len();
31844 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31845 } else {
31846 __tmp.len()
31847 }
31848 }
31849}
31850#[doc = "id: 126"]
31851#[doc = "Control a serial port. This can be used for raw access to an onboard serial peripheral such as a GPS or telemetry radio. It is designed to make it possible to update the devices firmware via MAVLink messages or change the devices settings. A message with zero bytes can be used to change just the baudrate."]
31852#[derive(Debug, Clone, PartialEq)]
31853#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31854#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31855pub struct SERIAL_CONTROL_DATA {
31856 #[doc = "Baudrate of transfer. Zero means no change."]
31857 pub baudrate: u32,
31858 #[doc = "Timeout for reply data"]
31859 pub timeout: u16,
31860 #[doc = "Serial control device type."]
31861 pub device: SerialControlDev,
31862 #[doc = "Bitmap of serial control flags."]
31863 pub flags: SerialControlFlag,
31864 #[doc = "how many bytes in this transfer"]
31865 pub count: u8,
31866 #[doc = "serial data"]
31867 #[cfg_attr(feature = "serde", serde(with = "serde_arrays"))]
31868 pub data: [u8; 70],
31869 #[doc = "System ID"]
31870 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31871 pub target_system: u8,
31872 #[doc = "Component ID"]
31873 #[cfg_attr(feature = "serde", serde(default = "crate::RustDefault::rust_default"))]
31874 pub target_component: u8,
31875}
31876impl SERIAL_CONTROL_DATA {
31877 pub const ENCODED_LEN: usize = 81usize;
31878 pub const DEFAULT: Self = Self {
31879 baudrate: 0_u32,
31880 timeout: 0_u16,
31881 device: SerialControlDev::DEFAULT,
31882 flags: SerialControlFlag::DEFAULT,
31883 count: 0_u8,
31884 data: [0_u8; 70usize],
31885 target_system: 0_u8,
31886 target_component: 0_u8,
31887 };
31888 #[cfg(feature = "arbitrary")]
31889 pub fn random<R: rand::RngCore>(rng: &mut R) -> Self {
31890 use arbitrary::{Arbitrary, Unstructured};
31891 let mut buf = [0u8; 1024];
31892 rng.fill_bytes(&mut buf);
31893 let mut unstructured = Unstructured::new(&buf);
31894 Self::arbitrary(&mut unstructured).unwrap_or_default()
31895 }
31896}
31897impl Default for SERIAL_CONTROL_DATA {
31898 fn default() -> Self {
31899 Self::DEFAULT.clone()
31900 }
31901}
31902impl MessageData for SERIAL_CONTROL_DATA {
31903 type Message = MavMessage;
31904 const ID: u32 = 126u32;
31905 const NAME: &'static str = "SERIAL_CONTROL";
31906 const EXTRA_CRC: u8 = 220u8;
31907 const ENCODED_LEN: usize = 81usize;
31908 fn deser(
31909 _version: MavlinkVersion,
31910 __input: &[u8],
31911 ) -> Result<Self, ::mavlink_core::error::ParserError> {
31912 let avail_len = __input.len();
31913 let mut payload_buf = [0; Self::ENCODED_LEN];
31914 let mut buf = if avail_len < Self::ENCODED_LEN {
31915 payload_buf[0..avail_len].copy_from_slice(__input);
31916 Bytes::new(&payload_buf)
31917 } else {
31918 Bytes::new(__input)
31919 };
31920 let mut __struct = Self::default();
31921 __struct.baudrate = buf.get_u32_le();
31922 __struct.timeout = buf.get_u16_le();
31923 let tmp = buf.get_u8();
31924 __struct.device =
31925 FromPrimitive::from_u8(tmp).ok_or(::mavlink_core::error::ParserError::InvalidEnum {
31926 enum_type: "SerialControlDev",
31927 value: tmp as u32,
31928 })?;
31929 let tmp = buf.get_u8();
31930 __struct.flags = SerialControlFlag::from_bits(tmp & SerialControlFlag::all().bits())
31931 .ok_or(::mavlink_core::error::ParserError::InvalidFlag {
31932 flag_type: "SerialControlFlag",
31933 value: tmp as u32,
31934 })?;
31935 __struct.count = buf.get_u8();
31936 for v in &mut __struct.data {
31937 let val = buf.get_u8();
31938 *v = val;
31939 }
31940 __struct.target_system = buf.get_u8();
31941 __struct.target_component = buf.get_u8();
31942 Ok(__struct)
31943 }
31944 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
31945 let mut __tmp = BytesMut::new(bytes);
31946 #[allow(clippy::absurd_extreme_comparisons)]
31947 #[allow(unused_comparisons)]
31948 if __tmp.remaining() < Self::ENCODED_LEN {
31949 panic!(
31950 "buffer is too small (need {} bytes, but got {})",
31951 Self::ENCODED_LEN,
31952 __tmp.remaining(),
31953 )
31954 }
31955 __tmp.put_u32_le(self.baudrate);
31956 __tmp.put_u16_le(self.timeout);
31957 __tmp.put_u8(self.device as u8);
31958 __tmp.put_u8(self.flags.bits());
31959 __tmp.put_u8(self.count);
31960 for val in &self.data {
31961 __tmp.put_u8(*val);
31962 }
31963 __tmp.put_u8(self.target_system);
31964 __tmp.put_u8(self.target_component);
31965 if matches!(version, MavlinkVersion::V2) {
31966 let len = __tmp.len();
31967 ::mavlink_core::utils::remove_trailing_zeroes(&bytes[..len])
31968 } else {
31969 __tmp.len()
31970 }
31971 }
31972}
31973#[derive(Clone, PartialEq, Debug)]
31974#[cfg_attr(feature = "serde", derive(Serialize, Deserialize))]
31975#[cfg_attr(feature = "serde", serde(tag = "type"))]
31976#[cfg_attr(feature = "arbitrary", derive(Arbitrary))]
31977#[repr(u32)]
31978pub enum MavMessage {
31979 MISSION_COUNT(MISSION_COUNT_DATA),
31980 SYSTEM_TIME(SYSTEM_TIME_DATA),
31981 SYS_STATUS(SYS_STATUS_DATA),
31982 ADSB_VEHICLE(ADSB_VEHICLE_DATA),
31983 TUNNEL(TUNNEL_DATA),
31984 OPEN_DRONE_ID_ARM_STATUS(OPEN_DRONE_ID_ARM_STATUS_DATA),
31985 RAW_IMU(RAW_IMU_DATA),
31986 MISSION_CURRENT(MISSION_CURRENT_DATA),
31987 HIL_STATE(HIL_STATE_DATA),
31988 OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA),
31989 TRAJECTORY_REPRESENTATION_WAYPOINTS(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA),
31990 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA),
31991 CAMERA_IMAGE_CAPTURED(CAMERA_IMAGE_CAPTURED_DATA),
31992 PROTOCOL_VERSION(PROTOCOL_VERSION_DATA),
31993 GPS2_RAW(GPS2_RAW_DATA),
31994 UTM_GLOBAL_POSITION(UTM_GLOBAL_POSITION_DATA),
31995 HIL_GPS(HIL_GPS_DATA),
31996 HIGH_LATENCY(HIGH_LATENCY_DATA),
31997 OPEN_DRONE_ID_BASIC_ID(OPEN_DRONE_ID_BASIC_ID_DATA),
31998 BATTERY_STATUS(BATTERY_STATUS_DATA),
31999 EFI_STATUS(EFI_STATUS_DATA),
32000 WINCH_STATUS(WINCH_STATUS_DATA),
32001 UAVIONIX_ADSB_OUT_CFG_FLIGHTID(UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA),
32002 PING(PING_DATA),
32003 HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA),
32004 VIDEO_STREAM_INFORMATION(VIDEO_STREAM_INFORMATION_DATA),
32005 LOCAL_POSITION_NED_COV(LOCAL_POSITION_NED_COV_DATA),
32006 AUTH_KEY(AUTH_KEY_DATA),
32007 HIL_ACTUATOR_CONTROLS(HIL_ACTUATOR_CONTROLS_DATA),
32008 COLLISION(COLLISION_DATA),
32009 UAVIONIX_ADSB_OUT_CFG_REGISTRATION(UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA),
32010 HIL_STATE_QUATERNION(HIL_STATE_QUATERNION_DATA),
32011 UAVIONIX_ADSB_OUT_STATUS(UAVIONIX_ADSB_OUT_STATUS_DATA),
32012 MISSION_ACK(MISSION_ACK_DATA),
32013 WHEEL_DISTANCE(WHEEL_DISTANCE_DATA),
32014 OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA),
32015 CAMERA_TRACKING_GEO_STATUS(CAMERA_TRACKING_GEO_STATUS_DATA),
32016 CELLULAR_CONFIG(CELLULAR_CONFIG_DATA),
32017 DATA_STREAM(DATA_STREAM_DATA),
32018 PARAM_SET(PARAM_SET_DATA),
32019 UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA),
32020 STORAGE_INFORMATION(STORAGE_INFORMATION_DATA),
32021 MISSION_REQUEST_INT(MISSION_REQUEST_INT_DATA),
32022 SCALED_PRESSURE(SCALED_PRESSURE_DATA),
32023 ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA),
32024 PLAY_TUNE(PLAY_TUNE_DATA),
32025 CANFD_FRAME(CANFD_FRAME_DATA),
32026 AVAILABLE_MODES_MONITOR(AVAILABLE_MODES_MONITOR_DATA),
32027 DEBUG(DEBUG_DATA),
32028 CAN_FRAME(CAN_FRAME_DATA),
32029 MANUAL_SETPOINT(MANUAL_SETPOINT_DATA),
32030 MISSION_SET_CURRENT(MISSION_SET_CURRENT_DATA),
32031 BUTTON_CHANGE(BUTTON_CHANGE_DATA),
32032 CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA),
32033 LOG_DATA(LOG_DATA_DATA),
32034 DEBUG_VECT(DEBUG_VECT_DATA),
32035 PLAY_TUNE_V2(PLAY_TUNE_V2_DATA),
32036 OPEN_DRONE_ID_SELF_ID(OPEN_DRONE_ID_SELF_ID_DATA),
32037 COMMAND_CANCEL(COMMAND_CANCEL_DATA),
32038 UAVIONIX_ADSB_OUT_CONTROL(UAVIONIX_ADSB_OUT_CONTROL_DATA),
32039 RESPONSE_EVENT_ERROR(RESPONSE_EVENT_ERROR_DATA),
32040 HEARTBEAT(HEARTBEAT_DATA),
32041 EVENT(EVENT_DATA),
32042 DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA),
32043 COMMAND_INT(COMMAND_INT_DATA),
32044 FILE_TRANSFER_PROTOCOL(FILE_TRANSFER_PROTOCOL_DATA),
32045 CELLULAR_STATUS(CELLULAR_STATUS_DATA),
32046 REQUEST_DATA_STREAM(REQUEST_DATA_STREAM_DATA),
32047 PARAM_EXT_REQUEST_LIST(PARAM_EXT_REQUEST_LIST_DATA),
32048 WIND_COV(WIND_COV_DATA),
32049 ATTITUDE(ATTITUDE_DATA),
32050 RADIO_STATUS(RADIO_STATUS_DATA),
32051 NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA),
32052 GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA),
32053 POSITION_TARGET_GLOBAL_INT(POSITION_TARGET_GLOBAL_INT_DATA),
32054 GPS_STATUS(GPS_STATUS_DATA),
32055 PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA),
32056 OPEN_DRONE_ID_SYSTEM_UPDATE(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA),
32057 FUEL_STATUS(FUEL_STATUS_DATA),
32058 MEMORY_VECT(MEMORY_VECT_DATA),
32059 UAVIONIX_ADSB_OUT_DYNAMIC(UAVIONIX_ADSB_OUT_DYNAMIC_DATA),
32060 CAMERA_SETTINGS(CAMERA_SETTINGS_DATA),
32061 SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA),
32062 ACTUATOR_CONTROL_TARGET(ACTUATOR_CONTROL_TARGET_DATA),
32063 ATTITUDE_TARGET(ATTITUDE_TARGET_DATA),
32064 SCALED_IMU(SCALED_IMU_DATA),
32065 STATUSTEXT(STATUSTEXT_DATA),
32066 ALTITUDE(ALTITUDE_DATA),
32067 CHANGE_OPERATOR_CONTROL(CHANGE_OPERATOR_CONTROL_DATA),
32068 RAW_RPM(RAW_RPM_DATA),
32069 GPS2_RTK(GPS2_RTK_DATA),
32070 OPTICAL_FLOW(OPTICAL_FLOW_DATA),
32071 TERRAIN_DATA(TERRAIN_DATA_DATA),
32072 ORBIT_EXECUTION_STATUS(ORBIT_EXECUTION_STATUS_DATA),
32073 GLOBAL_POSITION_INT(GLOBAL_POSITION_INT_DATA),
32074 TERRAIN_REPORT(TERRAIN_REPORT_DATA),
32075 SAFETY_SET_ALLOWED_AREA(SAFETY_SET_ALLOWED_AREA_DATA),
32076 SET_HOME_POSITION(SET_HOME_POSITION_DATA),
32077 AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA),
32078 SETUP_SIGNING(SETUP_SIGNING_DATA),
32079 ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA),
32080 UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA),
32081 GIMBAL_DEVICE_INFORMATION(GIMBAL_DEVICE_INFORMATION_DATA),
32082 GIMBAL_MANAGER_SET_ATTITUDE(GIMBAL_MANAGER_SET_ATTITUDE_DATA),
32083 LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA),
32084 RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA),
32085 LINK_NODE_STATUS(LINK_NODE_STATUS_DATA),
32086 MISSION_ITEM_REACHED(MISSION_ITEM_REACHED_DATA),
32087 SET_POSITION_TARGET_GLOBAL_INT(SET_POSITION_TARGET_GLOBAL_INT_DATA),
32088 SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA),
32089 SET_GPS_GLOBAL_ORIGIN(SET_GPS_GLOBAL_ORIGIN_DATA),
32090 VIBRATION(VIBRATION_DATA),
32091 GIMBAL_MANAGER_STATUS(GIMBAL_MANAGER_STATUS_DATA),
32092 MISSION_ITEM_INT(MISSION_ITEM_INT_DATA),
32093 POWER_STATUS(POWER_STATUS_DATA),
32094 LOGGING_DATA(LOGGING_DATA_DATA),
32095 CHANGE_OPERATOR_CONTROL_ACK(CHANGE_OPERATOR_CONTROL_ACK_DATA),
32096 GPS_RTK(GPS_RTK_DATA),
32097 FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA),
32098 SUPPORTED_TUNES(SUPPORTED_TUNES_DATA),
32099 WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA),
32100 TERRAIN_CHECK(TERRAIN_CHECK_DATA),
32101 RAW_PRESSURE(RAW_PRESSURE_DATA),
32102 OPEN_DRONE_ID_AUTHENTICATION(OPEN_DRONE_ID_AUTHENTICATION_DATA),
32103 ESC_INFO(ESC_INFO_DATA),
32104 DISTANCE_SENSOR(DISTANCE_SENSOR_DATA),
32105 HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA),
32106 ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA),
32107 RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA),
32108 SCALED_IMU2(SCALED_IMU2_DATA),
32109 HIL_SENSOR(HIL_SENSOR_DATA),
32110 RESOURCE_REQUEST(RESOURCE_REQUEST_DATA),
32111 CAMERA_THERMAL_RANGE(CAMERA_THERMAL_RANGE_DATA),
32112 TIMESYNC(TIMESYNC_DATA),
32113 OPEN_DRONE_ID_MESSAGE_PACK(OPEN_DRONE_ID_MESSAGE_PACK_DATA),
32114 LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA),
32115 COMPONENT_METADATA(COMPONENT_METADATA_DATA),
32116 MAG_CAL_REPORT(MAG_CAL_REPORT_DATA),
32117 NAMED_VALUE_INT(NAMED_VALUE_INT_DATA),
32118 SAFETY_ALLOWED_AREA(SAFETY_ALLOWED_AREA_DATA),
32119 GIMBAL_DEVICE_ATTITUDE_STATUS(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA),
32120 ESC_STATUS(ESC_STATUS_DATA),
32121 PARAM_EXT_REQUEST_READ(PARAM_EXT_REQUEST_READ_DATA),
32122 SCALED_IMU3(SCALED_IMU3_DATA),
32123 ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA),
32124 PARAM_EXT_ACK(PARAM_EXT_ACK_DATA),
32125 V2_EXTENSION(V2_EXTENSION_DATA),
32126 SET_ACTUATOR_CONTROL_TARGET(SET_ACTUATOR_CONTROL_TARGET_DATA),
32127 RC_CHANNELS_OVERRIDE(RC_CHANNELS_OVERRIDE_DATA),
32128 DATA_TRANSMISSION_HANDSHAKE(DATA_TRANSMISSION_HANDSHAKE_DATA),
32129 LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA),
32130 EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA),
32131 FENCE_STATUS(FENCE_STATUS_DATA),
32132 ONBOARD_COMPUTER_STATUS(ONBOARD_COMPUTER_STATUS_DATA),
32133 MISSION_REQUEST_LIST(MISSION_REQUEST_LIST_DATA),
32134 MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA),
32135 TERRAIN_REQUEST(TERRAIN_REQUEST_DATA),
32136 SCALED_PRESSURE3(SCALED_PRESSURE3_DATA),
32137 REQUEST_EVENT(REQUEST_EVENT_DATA),
32138 SET_ATTITUDE_TARGET(SET_ATTITUDE_TARGET_DATA),
32139 SET_POSITION_TARGET_LOCAL_NED(SET_POSITION_TARGET_LOCAL_NED_DATA),
32140 LOGGING_ACK(LOGGING_ACK_DATA),
32141 LOG_ERASE(LOG_ERASE_DATA),
32142 OPEN_DRONE_ID_LOCATION(OPEN_DRONE_ID_LOCATION_DATA),
32143 UAVIONIX_ADSB_OUT_CFG(UAVIONIX_ADSB_OUT_CFG_DATA),
32144 TRAJECTORY_REPRESENTATION_BEZIER(TRAJECTORY_REPRESENTATION_BEZIER_DATA),
32145 SIM_STATE(SIM_STATE_DATA),
32146 ODOMETRY(ODOMETRY_DATA),
32147 VISION_POSITION_ESTIMATE(VISION_POSITION_ESTIMATE_DATA),
32148 PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA),
32149 BATTERY_INFO(BATTERY_INFO_DATA),
32150 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA),
32151 VIDEO_STREAM_STATUS(VIDEO_STREAM_STATUS_DATA),
32152 ATT_POS_MOCAP(ATT_POS_MOCAP_DATA),
32153 UAVIONIX_ADSB_GET(UAVIONIX_ADSB_GET_DATA),
32154 MISSION_ITEM(MISSION_ITEM_DATA),
32155 VISION_SPEED_ESTIMATE(VISION_SPEED_ESTIMATE_DATA),
32156 MISSION_WRITE_PARTIAL_LIST(MISSION_WRITE_PARTIAL_LIST_DATA),
32157 VFR_HUD(VFR_HUD_DATA),
32158 POSITION_TARGET_LOCAL_NED(POSITION_TARGET_LOCAL_NED_DATA),
32159 MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA),
32160 MANUAL_CONTROL(MANUAL_CONTROL_DATA),
32161 AVAILABLE_MODES(AVAILABLE_MODES_DATA),
32162 TIME_ESTIMATE_TO_TARGET(TIME_ESTIMATE_TO_TARGET_DATA),
32163 GPS_RAW_INT(GPS_RAW_INT_DATA),
32164 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA),
32165 VICON_POSITION_ESTIMATE(VICON_POSITION_ESTIMATE_DATA),
32166 SCALED_PRESSURE2(SCALED_PRESSURE2_DATA),
32167 CONTROL_SYSTEM_STATE(CONTROL_SYSTEM_STATE_DATA),
32168 MISSION_REQUEST_PARTIAL_LIST(MISSION_REQUEST_PARTIAL_LIST_DATA),
32169 HOME_POSITION(HOME_POSITION_DATA),
32170 CAMERA_TRACKING_IMAGE_STATUS(CAMERA_TRACKING_IMAGE_STATUS_DATA),
32171 ACTUATOR_OUTPUT_STATUS(ACTUATOR_OUTPUT_STATUS_DATA),
32172 LOG_REQUEST_END(LOG_REQUEST_END_DATA),
32173 RC_CHANNELS(RC_CHANNELS_DATA),
32174 ATTITUDE_QUATERNION_COV(ATTITUDE_QUATERNION_COV_DATA),
32175 CAMERA_TRIGGER(CAMERA_TRIGGER_DATA),
32176 FOLLOW_TARGET(FOLLOW_TARGET_DATA),
32177 GLOBAL_POSITION_INT_COV(GLOBAL_POSITION_INT_COV_DATA),
32178 MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA),
32179 GENERATOR_STATUS(GENERATOR_STATUS_DATA),
32180 GPS_RTCM_DATA(GPS_RTCM_DATA_DATA),
32181 NAV_CONTROLLER_OUTPUT(NAV_CONTROLLER_OUTPUT_DATA),
32182 GLOBAL_VISION_POSITION_ESTIMATE(GLOBAL_VISION_POSITION_ESTIMATE_DATA),
32183 PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA),
32184 CAMERA_CAPTURE_STATUS(CAMERA_CAPTURE_STATUS_DATA),
32185 GIMBAL_MANAGER_SET_MANUAL_CONTROL(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA),
32186 GIMBAL_MANAGER_INFORMATION(GIMBAL_MANAGER_INFORMATION_DATA),
32187 HIGH_LATENCY2(HIGH_LATENCY2_DATA),
32188 HIGHRES_IMU(HIGHRES_IMU_DATA),
32189 HIL_CONTROLS(HIL_CONTROLS_DATA),
32190 MISSION_REQUEST(MISSION_REQUEST_DATA),
32191 LANDING_TARGET(LANDING_TARGET_DATA),
32192 LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA),
32193 CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA),
32194 LOG_ENTRY(LOG_ENTRY_DATA),
32195 GPS_INJECT_DATA(GPS_INJECT_DATA_DATA),
32196 PARAM_VALUE(PARAM_VALUE_DATA),
32197 GIMBAL_MANAGER_SET_PITCHYAW(GIMBAL_MANAGER_SET_PITCHYAW_DATA),
32198 CURRENT_EVENT_SEQUENCE(CURRENT_EVENT_SEQUENCE_DATA),
32199 CAMERA_INFORMATION(CAMERA_INFORMATION_DATA),
32200 OPEN_DRONE_ID_OPERATOR_ID(OPEN_DRONE_ID_OPERATOR_ID_DATA),
32201 COMPONENT_INFORMATION(COMPONENT_INFORMATION_DATA),
32202 COMMAND_LONG(COMMAND_LONG_DATA),
32203 PARAM_EXT_SET(PARAM_EXT_SET_DATA),
32204 GPS_INPUT(GPS_INPUT_DATA),
32205 SET_MODE(SET_MODE_DATA),
32206 AIS_VESSEL(AIS_VESSEL_DATA),
32207 ATTITUDE_QUATERNION(ATTITUDE_QUATERNION_DATA),
32208 CURRENT_MODE(CURRENT_MODE_DATA),
32209 GIMBAL_DEVICE_SET_ATTITUDE(GIMBAL_DEVICE_SET_ATTITUDE_DATA),
32210 HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA),
32211 PARAM_MAP_RC(PARAM_MAP_RC_DATA),
32212 COMPONENT_INFORMATION_BASIC(COMPONENT_INFORMATION_BASIC_DATA),
32213 OPEN_DRONE_ID_SYSTEM(OPEN_DRONE_ID_SYSTEM_DATA),
32214 COMMAND_ACK(COMMAND_ACK_DATA),
32215 SERIAL_CONTROL(SERIAL_CONTROL_DATA),
32216}
32217impl MavMessage {
32218 pub const fn all_ids() -> &'static [u32] {
32219 &[
32220 0u32, 1u32, 2u32, 4u32, 5u32, 6u32, 7u32, 8u32, 11u32, 20u32, 21u32, 22u32, 23u32,
32221 24u32, 25u32, 26u32, 27u32, 28u32, 29u32, 30u32, 31u32, 32u32, 33u32, 34u32, 35u32,
32222 36u32, 37u32, 38u32, 39u32, 40u32, 41u32, 42u32, 43u32, 44u32, 45u32, 46u32, 47u32,
32223 48u32, 49u32, 50u32, 51u32, 54u32, 55u32, 61u32, 62u32, 63u32, 64u32, 65u32, 66u32,
32224 67u32, 69u32, 70u32, 73u32, 74u32, 75u32, 76u32, 77u32, 80u32, 81u32, 82u32, 83u32,
32225 84u32, 85u32, 86u32, 87u32, 89u32, 90u32, 91u32, 92u32, 93u32, 100u32, 101u32, 102u32,
32226 103u32, 104u32, 105u32, 106u32, 107u32, 108u32, 109u32, 110u32, 111u32, 112u32, 113u32,
32227 114u32, 115u32, 116u32, 117u32, 118u32, 119u32, 120u32, 121u32, 122u32, 123u32, 124u32,
32228 125u32, 126u32, 127u32, 128u32, 129u32, 130u32, 131u32, 132u32, 133u32, 134u32, 135u32,
32229 136u32, 137u32, 138u32, 139u32, 140u32, 141u32, 142u32, 143u32, 144u32, 146u32, 147u32,
32230 148u32, 149u32, 162u32, 192u32, 225u32, 230u32, 231u32, 232u32, 233u32, 234u32, 235u32,
32231 241u32, 242u32, 243u32, 244u32, 245u32, 246u32, 247u32, 248u32, 249u32, 250u32, 251u32,
32232 252u32, 253u32, 254u32, 256u32, 257u32, 258u32, 259u32, 260u32, 261u32, 262u32, 263u32,
32233 264u32, 265u32, 266u32, 267u32, 268u32, 269u32, 270u32, 271u32, 275u32, 276u32, 277u32,
32234 280u32, 281u32, 282u32, 283u32, 284u32, 285u32, 286u32, 287u32, 288u32, 290u32, 291u32,
32235 299u32, 300u32, 301u32, 310u32, 311u32, 320u32, 321u32, 322u32, 323u32, 324u32, 330u32,
32236 331u32, 332u32, 333u32, 334u32, 335u32, 336u32, 339u32, 340u32, 350u32, 360u32, 370u32,
32237 371u32, 372u32, 373u32, 375u32, 380u32, 385u32, 386u32, 387u32, 388u32, 390u32, 395u32,
32238 396u32, 397u32, 400u32, 401u32, 410u32, 411u32, 412u32, 413u32, 435u32, 436u32, 437u32,
32239 440u32, 9000u32, 9005u32, 10001u32, 10002u32, 10003u32, 10004u32, 10005u32, 10006u32,
32240 10007u32, 10008u32, 12900u32, 12901u32, 12902u32, 12903u32, 12904u32, 12905u32,
32241 12915u32, 12918u32, 12919u32, 12920u32,
32242 ]
32243 }
32244}
32245impl Message for MavMessage {
32246 fn parse(
32247 version: MavlinkVersion,
32248 id: u32,
32249 payload: &[u8],
32250 ) -> Result<Self, ::mavlink_core::error::ParserError> {
32251 match id {
32252 MISSION_COUNT_DATA::ID => {
32253 MISSION_COUNT_DATA::deser(version, payload).map(Self::MISSION_COUNT)
32254 }
32255 SYSTEM_TIME_DATA::ID => {
32256 SYSTEM_TIME_DATA::deser(version, payload).map(Self::SYSTEM_TIME)
32257 }
32258 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::deser(version, payload).map(Self::SYS_STATUS),
32259 ADSB_VEHICLE_DATA::ID => {
32260 ADSB_VEHICLE_DATA::deser(version, payload).map(Self::ADSB_VEHICLE)
32261 }
32262 TUNNEL_DATA::ID => TUNNEL_DATA::deser(version, payload).map(Self::TUNNEL),
32263 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => {
32264 OPEN_DRONE_ID_ARM_STATUS_DATA::deser(version, payload)
32265 .map(Self::OPEN_DRONE_ID_ARM_STATUS)
32266 }
32267 RAW_IMU_DATA::ID => RAW_IMU_DATA::deser(version, payload).map(Self::RAW_IMU),
32268 MISSION_CURRENT_DATA::ID => {
32269 MISSION_CURRENT_DATA::deser(version, payload).map(Self::MISSION_CURRENT)
32270 }
32271 HIL_STATE_DATA::ID => HIL_STATE_DATA::deser(version, payload).map(Self::HIL_STATE),
32272 OBSTACLE_DISTANCE_DATA::ID => {
32273 OBSTACLE_DISTANCE_DATA::deser(version, payload).map(Self::OBSTACLE_DISTANCE)
32274 }
32275 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
32276 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::deser(version, payload)
32277 .map(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS)
32278 }
32279 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
32280 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::deser(version, payload)
32281 .map(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE)
32282 }
32283 CAMERA_IMAGE_CAPTURED_DATA::ID => {
32284 CAMERA_IMAGE_CAPTURED_DATA::deser(version, payload).map(Self::CAMERA_IMAGE_CAPTURED)
32285 }
32286 PROTOCOL_VERSION_DATA::ID => {
32287 PROTOCOL_VERSION_DATA::deser(version, payload).map(Self::PROTOCOL_VERSION)
32288 }
32289 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::deser(version, payload).map(Self::GPS2_RAW),
32290 UTM_GLOBAL_POSITION_DATA::ID => {
32291 UTM_GLOBAL_POSITION_DATA::deser(version, payload).map(Self::UTM_GLOBAL_POSITION)
32292 }
32293 HIL_GPS_DATA::ID => HIL_GPS_DATA::deser(version, payload).map(Self::HIL_GPS),
32294 HIGH_LATENCY_DATA::ID => {
32295 HIGH_LATENCY_DATA::deser(version, payload).map(Self::HIGH_LATENCY)
32296 }
32297 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::deser(version, payload)
32298 .map(Self::OPEN_DRONE_ID_BASIC_ID),
32299 BATTERY_STATUS_DATA::ID => {
32300 BATTERY_STATUS_DATA::deser(version, payload).map(Self::BATTERY_STATUS)
32301 }
32302 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::deser(version, payload).map(Self::EFI_STATUS),
32303 WINCH_STATUS_DATA::ID => {
32304 WINCH_STATUS_DATA::deser(version, payload).map(Self::WINCH_STATUS)
32305 }
32306 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => {
32307 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::deser(version, payload)
32308 .map(Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID)
32309 }
32310 PING_DATA::ID => PING_DATA::deser(version, payload).map(Self::PING),
32311 HIL_OPTICAL_FLOW_DATA::ID => {
32312 HIL_OPTICAL_FLOW_DATA::deser(version, payload).map(Self::HIL_OPTICAL_FLOW)
32313 }
32314 VIDEO_STREAM_INFORMATION_DATA::ID => {
32315 VIDEO_STREAM_INFORMATION_DATA::deser(version, payload)
32316 .map(Self::VIDEO_STREAM_INFORMATION)
32317 }
32318 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::deser(version, payload)
32319 .map(Self::LOCAL_POSITION_NED_COV),
32320 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::deser(version, payload).map(Self::AUTH_KEY),
32321 HIL_ACTUATOR_CONTROLS_DATA::ID => {
32322 HIL_ACTUATOR_CONTROLS_DATA::deser(version, payload).map(Self::HIL_ACTUATOR_CONTROLS)
32323 }
32324 COLLISION_DATA::ID => COLLISION_DATA::deser(version, payload).map(Self::COLLISION),
32325 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
32326 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::deser(version, payload)
32327 .map(Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION)
32328 }
32329 HIL_STATE_QUATERNION_DATA::ID => {
32330 HIL_STATE_QUATERNION_DATA::deser(version, payload).map(Self::HIL_STATE_QUATERNION)
32331 }
32332 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => {
32333 UAVIONIX_ADSB_OUT_STATUS_DATA::deser(version, payload)
32334 .map(Self::UAVIONIX_ADSB_OUT_STATUS)
32335 }
32336 MISSION_ACK_DATA::ID => {
32337 MISSION_ACK_DATA::deser(version, payload).map(Self::MISSION_ACK)
32338 }
32339 WHEEL_DISTANCE_DATA::ID => {
32340 WHEEL_DISTANCE_DATA::deser(version, payload).map(Self::WHEEL_DISTANCE)
32341 }
32342 OPTICAL_FLOW_RAD_DATA::ID => {
32343 OPTICAL_FLOW_RAD_DATA::deser(version, payload).map(Self::OPTICAL_FLOW_RAD)
32344 }
32345 CAMERA_TRACKING_GEO_STATUS_DATA::ID => {
32346 CAMERA_TRACKING_GEO_STATUS_DATA::deser(version, payload)
32347 .map(Self::CAMERA_TRACKING_GEO_STATUS)
32348 }
32349 CELLULAR_CONFIG_DATA::ID => {
32350 CELLULAR_CONFIG_DATA::deser(version, payload).map(Self::CELLULAR_CONFIG)
32351 }
32352 DATA_STREAM_DATA::ID => {
32353 DATA_STREAM_DATA::deser(version, payload).map(Self::DATA_STREAM)
32354 }
32355 PARAM_SET_DATA::ID => PARAM_SET_DATA::deser(version, payload).map(Self::PARAM_SET),
32356 UAVCAN_NODE_STATUS_DATA::ID => {
32357 UAVCAN_NODE_STATUS_DATA::deser(version, payload).map(Self::UAVCAN_NODE_STATUS)
32358 }
32359 STORAGE_INFORMATION_DATA::ID => {
32360 STORAGE_INFORMATION_DATA::deser(version, payload).map(Self::STORAGE_INFORMATION)
32361 }
32362 MISSION_REQUEST_INT_DATA::ID => {
32363 MISSION_REQUEST_INT_DATA::deser(version, payload).map(Self::MISSION_REQUEST_INT)
32364 }
32365 SCALED_PRESSURE_DATA::ID => {
32366 SCALED_PRESSURE_DATA::deser(version, payload).map(Self::SCALED_PRESSURE)
32367 }
32368 ENCAPSULATED_DATA_DATA::ID => {
32369 ENCAPSULATED_DATA_DATA::deser(version, payload).map(Self::ENCAPSULATED_DATA)
32370 }
32371 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::deser(version, payload).map(Self::PLAY_TUNE),
32372 CANFD_FRAME_DATA::ID => {
32373 CANFD_FRAME_DATA::deser(version, payload).map(Self::CANFD_FRAME)
32374 }
32375 AVAILABLE_MODES_MONITOR_DATA::ID => {
32376 AVAILABLE_MODES_MONITOR_DATA::deser(version, payload)
32377 .map(Self::AVAILABLE_MODES_MONITOR)
32378 }
32379 DEBUG_DATA::ID => DEBUG_DATA::deser(version, payload).map(Self::DEBUG),
32380 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::deser(version, payload).map(Self::CAN_FRAME),
32381 MANUAL_SETPOINT_DATA::ID => {
32382 MANUAL_SETPOINT_DATA::deser(version, payload).map(Self::MANUAL_SETPOINT)
32383 }
32384 MISSION_SET_CURRENT_DATA::ID => {
32385 MISSION_SET_CURRENT_DATA::deser(version, payload).map(Self::MISSION_SET_CURRENT)
32386 }
32387 BUTTON_CHANGE_DATA::ID => {
32388 BUTTON_CHANGE_DATA::deser(version, payload).map(Self::BUTTON_CHANGE)
32389 }
32390 CAN_FILTER_MODIFY_DATA::ID => {
32391 CAN_FILTER_MODIFY_DATA::deser(version, payload).map(Self::CAN_FILTER_MODIFY)
32392 }
32393 LOG_DATA_DATA::ID => LOG_DATA_DATA::deser(version, payload).map(Self::LOG_DATA),
32394 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::deser(version, payload).map(Self::DEBUG_VECT),
32395 PLAY_TUNE_V2_DATA::ID => {
32396 PLAY_TUNE_V2_DATA::deser(version, payload).map(Self::PLAY_TUNE_V2)
32397 }
32398 OPEN_DRONE_ID_SELF_ID_DATA::ID => {
32399 OPEN_DRONE_ID_SELF_ID_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SELF_ID)
32400 }
32401 COMMAND_CANCEL_DATA::ID => {
32402 COMMAND_CANCEL_DATA::deser(version, payload).map(Self::COMMAND_CANCEL)
32403 }
32404 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => {
32405 UAVIONIX_ADSB_OUT_CONTROL_DATA::deser(version, payload)
32406 .map(Self::UAVIONIX_ADSB_OUT_CONTROL)
32407 }
32408 RESPONSE_EVENT_ERROR_DATA::ID => {
32409 RESPONSE_EVENT_ERROR_DATA::deser(version, payload).map(Self::RESPONSE_EVENT_ERROR)
32410 }
32411 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::deser(version, payload).map(Self::HEARTBEAT),
32412 EVENT_DATA::ID => EVENT_DATA::deser(version, payload).map(Self::EVENT),
32413 DEBUG_FLOAT_ARRAY_DATA::ID => {
32414 DEBUG_FLOAT_ARRAY_DATA::deser(version, payload).map(Self::DEBUG_FLOAT_ARRAY)
32415 }
32416 COMMAND_INT_DATA::ID => {
32417 COMMAND_INT_DATA::deser(version, payload).map(Self::COMMAND_INT)
32418 }
32419 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::deser(version, payload)
32420 .map(Self::FILE_TRANSFER_PROTOCOL),
32421 CELLULAR_STATUS_DATA::ID => {
32422 CELLULAR_STATUS_DATA::deser(version, payload).map(Self::CELLULAR_STATUS)
32423 }
32424 REQUEST_DATA_STREAM_DATA::ID => {
32425 REQUEST_DATA_STREAM_DATA::deser(version, payload).map(Self::REQUEST_DATA_STREAM)
32426 }
32427 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::deser(version, payload)
32428 .map(Self::PARAM_EXT_REQUEST_LIST),
32429 WIND_COV_DATA::ID => WIND_COV_DATA::deser(version, payload).map(Self::WIND_COV),
32430 ATTITUDE_DATA::ID => ATTITUDE_DATA::deser(version, payload).map(Self::ATTITUDE),
32431 RADIO_STATUS_DATA::ID => {
32432 RADIO_STATUS_DATA::deser(version, payload).map(Self::RADIO_STATUS)
32433 }
32434 NAMED_VALUE_FLOAT_DATA::ID => {
32435 NAMED_VALUE_FLOAT_DATA::deser(version, payload).map(Self::NAMED_VALUE_FLOAT)
32436 }
32437 GPS_GLOBAL_ORIGIN_DATA::ID => {
32438 GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::GPS_GLOBAL_ORIGIN)
32439 }
32440 POSITION_TARGET_GLOBAL_INT_DATA::ID => {
32441 POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
32442 .map(Self::POSITION_TARGET_GLOBAL_INT)
32443 }
32444 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::deser(version, payload).map(Self::GPS_STATUS),
32445 PARAM_REQUEST_LIST_DATA::ID => {
32446 PARAM_REQUEST_LIST_DATA::deser(version, payload).map(Self::PARAM_REQUEST_LIST)
32447 }
32448 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => {
32449 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::deser(version, payload)
32450 .map(Self::OPEN_DRONE_ID_SYSTEM_UPDATE)
32451 }
32452 FUEL_STATUS_DATA::ID => {
32453 FUEL_STATUS_DATA::deser(version, payload).map(Self::FUEL_STATUS)
32454 }
32455 MEMORY_VECT_DATA::ID => {
32456 MEMORY_VECT_DATA::deser(version, payload).map(Self::MEMORY_VECT)
32457 }
32458 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => {
32459 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::deser(version, payload)
32460 .map(Self::UAVIONIX_ADSB_OUT_DYNAMIC)
32461 }
32462 CAMERA_SETTINGS_DATA::ID => {
32463 CAMERA_SETTINGS_DATA::deser(version, payload).map(Self::CAMERA_SETTINGS)
32464 }
32465 SERVO_OUTPUT_RAW_DATA::ID => {
32466 SERVO_OUTPUT_RAW_DATA::deser(version, payload).map(Self::SERVO_OUTPUT_RAW)
32467 }
32468 ACTUATOR_CONTROL_TARGET_DATA::ID => {
32469 ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
32470 .map(Self::ACTUATOR_CONTROL_TARGET)
32471 }
32472 ATTITUDE_TARGET_DATA::ID => {
32473 ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::ATTITUDE_TARGET)
32474 }
32475 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::deser(version, payload).map(Self::SCALED_IMU),
32476 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::deser(version, payload).map(Self::STATUSTEXT),
32477 ALTITUDE_DATA::ID => ALTITUDE_DATA::deser(version, payload).map(Self::ALTITUDE),
32478 CHANGE_OPERATOR_CONTROL_DATA::ID => {
32479 CHANGE_OPERATOR_CONTROL_DATA::deser(version, payload)
32480 .map(Self::CHANGE_OPERATOR_CONTROL)
32481 }
32482 RAW_RPM_DATA::ID => RAW_RPM_DATA::deser(version, payload).map(Self::RAW_RPM),
32483 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::deser(version, payload).map(Self::GPS2_RTK),
32484 OPTICAL_FLOW_DATA::ID => {
32485 OPTICAL_FLOW_DATA::deser(version, payload).map(Self::OPTICAL_FLOW)
32486 }
32487 TERRAIN_DATA_DATA::ID => {
32488 TERRAIN_DATA_DATA::deser(version, payload).map(Self::TERRAIN_DATA)
32489 }
32490 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::deser(version, payload)
32491 .map(Self::ORBIT_EXECUTION_STATUS),
32492 GLOBAL_POSITION_INT_DATA::ID => {
32493 GLOBAL_POSITION_INT_DATA::deser(version, payload).map(Self::GLOBAL_POSITION_INT)
32494 }
32495 TERRAIN_REPORT_DATA::ID => {
32496 TERRAIN_REPORT_DATA::deser(version, payload).map(Self::TERRAIN_REPORT)
32497 }
32498 SAFETY_SET_ALLOWED_AREA_DATA::ID => {
32499 SAFETY_SET_ALLOWED_AREA_DATA::deser(version, payload)
32500 .map(Self::SAFETY_SET_ALLOWED_AREA)
32501 }
32502 SET_HOME_POSITION_DATA::ID => {
32503 SET_HOME_POSITION_DATA::deser(version, payload).map(Self::SET_HOME_POSITION)
32504 }
32505 AUTOPILOT_VERSION_DATA::ID => {
32506 AUTOPILOT_VERSION_DATA::deser(version, payload).map(Self::AUTOPILOT_VERSION)
32507 }
32508 SETUP_SIGNING_DATA::ID => {
32509 SETUP_SIGNING_DATA::deser(version, payload).map(Self::SETUP_SIGNING)
32510 }
32511 ILLUMINATOR_STATUS_DATA::ID => {
32512 ILLUMINATOR_STATUS_DATA::deser(version, payload).map(Self::ILLUMINATOR_STATUS)
32513 }
32514 UAVCAN_NODE_INFO_DATA::ID => {
32515 UAVCAN_NODE_INFO_DATA::deser(version, payload).map(Self::UAVCAN_NODE_INFO)
32516 }
32517 GIMBAL_DEVICE_INFORMATION_DATA::ID => {
32518 GIMBAL_DEVICE_INFORMATION_DATA::deser(version, payload)
32519 .map(Self::GIMBAL_DEVICE_INFORMATION)
32520 }
32521 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => {
32522 GIMBAL_MANAGER_SET_ATTITUDE_DATA::deser(version, payload)
32523 .map(Self::GIMBAL_MANAGER_SET_ATTITUDE)
32524 }
32525 LOGGING_DATA_ACKED_DATA::ID => {
32526 LOGGING_DATA_ACKED_DATA::deser(version, payload).map(Self::LOGGING_DATA_ACKED)
32527 }
32528 RC_CHANNELS_RAW_DATA::ID => {
32529 RC_CHANNELS_RAW_DATA::deser(version, payload).map(Self::RC_CHANNELS_RAW)
32530 }
32531 LINK_NODE_STATUS_DATA::ID => {
32532 LINK_NODE_STATUS_DATA::deser(version, payload).map(Self::LINK_NODE_STATUS)
32533 }
32534 MISSION_ITEM_REACHED_DATA::ID => {
32535 MISSION_ITEM_REACHED_DATA::deser(version, payload).map(Self::MISSION_ITEM_REACHED)
32536 }
32537 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
32538 SET_POSITION_TARGET_GLOBAL_INT_DATA::deser(version, payload)
32539 .map(Self::SET_POSITION_TARGET_GLOBAL_INT)
32540 }
32541 SMART_BATTERY_INFO_DATA::ID => {
32542 SMART_BATTERY_INFO_DATA::deser(version, payload).map(Self::SMART_BATTERY_INFO)
32543 }
32544 SET_GPS_GLOBAL_ORIGIN_DATA::ID => {
32545 SET_GPS_GLOBAL_ORIGIN_DATA::deser(version, payload).map(Self::SET_GPS_GLOBAL_ORIGIN)
32546 }
32547 VIBRATION_DATA::ID => VIBRATION_DATA::deser(version, payload).map(Self::VIBRATION),
32548 GIMBAL_MANAGER_STATUS_DATA::ID => {
32549 GIMBAL_MANAGER_STATUS_DATA::deser(version, payload).map(Self::GIMBAL_MANAGER_STATUS)
32550 }
32551 MISSION_ITEM_INT_DATA::ID => {
32552 MISSION_ITEM_INT_DATA::deser(version, payload).map(Self::MISSION_ITEM_INT)
32553 }
32554 POWER_STATUS_DATA::ID => {
32555 POWER_STATUS_DATA::deser(version, payload).map(Self::POWER_STATUS)
32556 }
32557 LOGGING_DATA_DATA::ID => {
32558 LOGGING_DATA_DATA::deser(version, payload).map(Self::LOGGING_DATA)
32559 }
32560 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => {
32561 CHANGE_OPERATOR_CONTROL_ACK_DATA::deser(version, payload)
32562 .map(Self::CHANGE_OPERATOR_CONTROL_ACK)
32563 }
32564 GPS_RTK_DATA::ID => GPS_RTK_DATA::deser(version, payload).map(Self::GPS_RTK),
32565 FLIGHT_INFORMATION_DATA::ID => {
32566 FLIGHT_INFORMATION_DATA::deser(version, payload).map(Self::FLIGHT_INFORMATION)
32567 }
32568 SUPPORTED_TUNES_DATA::ID => {
32569 SUPPORTED_TUNES_DATA::deser(version, payload).map(Self::SUPPORTED_TUNES)
32570 }
32571 WIFI_CONFIG_AP_DATA::ID => {
32572 WIFI_CONFIG_AP_DATA::deser(version, payload).map(Self::WIFI_CONFIG_AP)
32573 }
32574 TERRAIN_CHECK_DATA::ID => {
32575 TERRAIN_CHECK_DATA::deser(version, payload).map(Self::TERRAIN_CHECK)
32576 }
32577 RAW_PRESSURE_DATA::ID => {
32578 RAW_PRESSURE_DATA::deser(version, payload).map(Self::RAW_PRESSURE)
32579 }
32580 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => {
32581 OPEN_DRONE_ID_AUTHENTICATION_DATA::deser(version, payload)
32582 .map(Self::OPEN_DRONE_ID_AUTHENTICATION)
32583 }
32584 ESC_INFO_DATA::ID => ESC_INFO_DATA::deser(version, payload).map(Self::ESC_INFO),
32585 DISTANCE_SENSOR_DATA::ID => {
32586 DISTANCE_SENSOR_DATA::deser(version, payload).map(Self::DISTANCE_SENSOR)
32587 }
32588 HIL_RC_INPUTS_RAW_DATA::ID => {
32589 HIL_RC_INPUTS_RAW_DATA::deser(version, payload).map(Self::HIL_RC_INPUTS_RAW)
32590 }
32591 ISBD_LINK_STATUS_DATA::ID => {
32592 ISBD_LINK_STATUS_DATA::deser(version, payload).map(Self::ISBD_LINK_STATUS)
32593 }
32594 RC_CHANNELS_SCALED_DATA::ID => {
32595 RC_CHANNELS_SCALED_DATA::deser(version, payload).map(Self::RC_CHANNELS_SCALED)
32596 }
32597 SCALED_IMU2_DATA::ID => {
32598 SCALED_IMU2_DATA::deser(version, payload).map(Self::SCALED_IMU2)
32599 }
32600 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::deser(version, payload).map(Self::HIL_SENSOR),
32601 RESOURCE_REQUEST_DATA::ID => {
32602 RESOURCE_REQUEST_DATA::deser(version, payload).map(Self::RESOURCE_REQUEST)
32603 }
32604 CAMERA_THERMAL_RANGE_DATA::ID => {
32605 CAMERA_THERMAL_RANGE_DATA::deser(version, payload).map(Self::CAMERA_THERMAL_RANGE)
32606 }
32607 TIMESYNC_DATA::ID => TIMESYNC_DATA::deser(version, payload).map(Self::TIMESYNC),
32608 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => {
32609 OPEN_DRONE_ID_MESSAGE_PACK_DATA::deser(version, payload)
32610 .map(Self::OPEN_DRONE_ID_MESSAGE_PACK)
32611 }
32612 LOG_REQUEST_DATA_DATA::ID => {
32613 LOG_REQUEST_DATA_DATA::deser(version, payload).map(Self::LOG_REQUEST_DATA)
32614 }
32615 COMPONENT_METADATA_DATA::ID => {
32616 COMPONENT_METADATA_DATA::deser(version, payload).map(Self::COMPONENT_METADATA)
32617 }
32618 MAG_CAL_REPORT_DATA::ID => {
32619 MAG_CAL_REPORT_DATA::deser(version, payload).map(Self::MAG_CAL_REPORT)
32620 }
32621 NAMED_VALUE_INT_DATA::ID => {
32622 NAMED_VALUE_INT_DATA::deser(version, payload).map(Self::NAMED_VALUE_INT)
32623 }
32624 SAFETY_ALLOWED_AREA_DATA::ID => {
32625 SAFETY_ALLOWED_AREA_DATA::deser(version, payload).map(Self::SAFETY_ALLOWED_AREA)
32626 }
32627 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => {
32628 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::deser(version, payload)
32629 .map(Self::GIMBAL_DEVICE_ATTITUDE_STATUS)
32630 }
32631 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::deser(version, payload).map(Self::ESC_STATUS),
32632 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::deser(version, payload)
32633 .map(Self::PARAM_EXT_REQUEST_READ),
32634 SCALED_IMU3_DATA::ID => {
32635 SCALED_IMU3_DATA::deser(version, payload).map(Self::SCALED_IMU3)
32636 }
32637 ESTIMATOR_STATUS_DATA::ID => {
32638 ESTIMATOR_STATUS_DATA::deser(version, payload).map(Self::ESTIMATOR_STATUS)
32639 }
32640 PARAM_EXT_ACK_DATA::ID => {
32641 PARAM_EXT_ACK_DATA::deser(version, payload).map(Self::PARAM_EXT_ACK)
32642 }
32643 V2_EXTENSION_DATA::ID => {
32644 V2_EXTENSION_DATA::deser(version, payload).map(Self::V2_EXTENSION)
32645 }
32646 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => {
32647 SET_ACTUATOR_CONTROL_TARGET_DATA::deser(version, payload)
32648 .map(Self::SET_ACTUATOR_CONTROL_TARGET)
32649 }
32650 RC_CHANNELS_OVERRIDE_DATA::ID => {
32651 RC_CHANNELS_OVERRIDE_DATA::deser(version, payload).map(Self::RC_CHANNELS_OVERRIDE)
32652 }
32653 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => {
32654 DATA_TRANSMISSION_HANDSHAKE_DATA::deser(version, payload)
32655 .map(Self::DATA_TRANSMISSION_HANDSHAKE)
32656 }
32657 LOCAL_POSITION_NED_DATA::ID => {
32658 LOCAL_POSITION_NED_DATA::deser(version, payload).map(Self::LOCAL_POSITION_NED)
32659 }
32660 EXTENDED_SYS_STATE_DATA::ID => {
32661 EXTENDED_SYS_STATE_DATA::deser(version, payload).map(Self::EXTENDED_SYS_STATE)
32662 }
32663 FENCE_STATUS_DATA::ID => {
32664 FENCE_STATUS_DATA::deser(version, payload).map(Self::FENCE_STATUS)
32665 }
32666 ONBOARD_COMPUTER_STATUS_DATA::ID => {
32667 ONBOARD_COMPUTER_STATUS_DATA::deser(version, payload)
32668 .map(Self::ONBOARD_COMPUTER_STATUS)
32669 }
32670 MISSION_REQUEST_LIST_DATA::ID => {
32671 MISSION_REQUEST_LIST_DATA::deser(version, payload).map(Self::MISSION_REQUEST_LIST)
32672 }
32673 MESSAGE_INTERVAL_DATA::ID => {
32674 MESSAGE_INTERVAL_DATA::deser(version, payload).map(Self::MESSAGE_INTERVAL)
32675 }
32676 TERRAIN_REQUEST_DATA::ID => {
32677 TERRAIN_REQUEST_DATA::deser(version, payload).map(Self::TERRAIN_REQUEST)
32678 }
32679 SCALED_PRESSURE3_DATA::ID => {
32680 SCALED_PRESSURE3_DATA::deser(version, payload).map(Self::SCALED_PRESSURE3)
32681 }
32682 REQUEST_EVENT_DATA::ID => {
32683 REQUEST_EVENT_DATA::deser(version, payload).map(Self::REQUEST_EVENT)
32684 }
32685 SET_ATTITUDE_TARGET_DATA::ID => {
32686 SET_ATTITUDE_TARGET_DATA::deser(version, payload).map(Self::SET_ATTITUDE_TARGET)
32687 }
32688 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => {
32689 SET_POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
32690 .map(Self::SET_POSITION_TARGET_LOCAL_NED)
32691 }
32692 LOGGING_ACK_DATA::ID => {
32693 LOGGING_ACK_DATA::deser(version, payload).map(Self::LOGGING_ACK)
32694 }
32695 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::deser(version, payload).map(Self::LOG_ERASE),
32696 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::deser(version, payload)
32697 .map(Self::OPEN_DRONE_ID_LOCATION),
32698 UAVIONIX_ADSB_OUT_CFG_DATA::ID => {
32699 UAVIONIX_ADSB_OUT_CFG_DATA::deser(version, payload).map(Self::UAVIONIX_ADSB_OUT_CFG)
32700 }
32701 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
32702 TRAJECTORY_REPRESENTATION_BEZIER_DATA::deser(version, payload)
32703 .map(Self::TRAJECTORY_REPRESENTATION_BEZIER)
32704 }
32705 SIM_STATE_DATA::ID => SIM_STATE_DATA::deser(version, payload).map(Self::SIM_STATE),
32706 ODOMETRY_DATA::ID => ODOMETRY_DATA::deser(version, payload).map(Self::ODOMETRY),
32707 VISION_POSITION_ESTIMATE_DATA::ID => {
32708 VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
32709 .map(Self::VISION_POSITION_ESTIMATE)
32710 }
32711 PARAM_REQUEST_READ_DATA::ID => {
32712 PARAM_REQUEST_READ_DATA::deser(version, payload).map(Self::PARAM_REQUEST_READ)
32713 }
32714 BATTERY_INFO_DATA::ID => {
32715 BATTERY_INFO_DATA::deser(version, payload).map(Self::BATTERY_INFO)
32716 }
32717 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
32718 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::deser(version, payload)
32719 .map(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET)
32720 }
32721 VIDEO_STREAM_STATUS_DATA::ID => {
32722 VIDEO_STREAM_STATUS_DATA::deser(version, payload).map(Self::VIDEO_STREAM_STATUS)
32723 }
32724 ATT_POS_MOCAP_DATA::ID => {
32725 ATT_POS_MOCAP_DATA::deser(version, payload).map(Self::ATT_POS_MOCAP)
32726 }
32727 UAVIONIX_ADSB_GET_DATA::ID => {
32728 UAVIONIX_ADSB_GET_DATA::deser(version, payload).map(Self::UAVIONIX_ADSB_GET)
32729 }
32730 MISSION_ITEM_DATA::ID => {
32731 MISSION_ITEM_DATA::deser(version, payload).map(Self::MISSION_ITEM)
32732 }
32733 VISION_SPEED_ESTIMATE_DATA::ID => {
32734 VISION_SPEED_ESTIMATE_DATA::deser(version, payload).map(Self::VISION_SPEED_ESTIMATE)
32735 }
32736 MISSION_WRITE_PARTIAL_LIST_DATA::ID => {
32737 MISSION_WRITE_PARTIAL_LIST_DATA::deser(version, payload)
32738 .map(Self::MISSION_WRITE_PARTIAL_LIST)
32739 }
32740 VFR_HUD_DATA::ID => VFR_HUD_DATA::deser(version, payload).map(Self::VFR_HUD),
32741 POSITION_TARGET_LOCAL_NED_DATA::ID => {
32742 POSITION_TARGET_LOCAL_NED_DATA::deser(version, payload)
32743 .map(Self::POSITION_TARGET_LOCAL_NED)
32744 }
32745 MISSION_CLEAR_ALL_DATA::ID => {
32746 MISSION_CLEAR_ALL_DATA::deser(version, payload).map(Self::MISSION_CLEAR_ALL)
32747 }
32748 MANUAL_CONTROL_DATA::ID => {
32749 MANUAL_CONTROL_DATA::deser(version, payload).map(Self::MANUAL_CONTROL)
32750 }
32751 AVAILABLE_MODES_DATA::ID => {
32752 AVAILABLE_MODES_DATA::deser(version, payload).map(Self::AVAILABLE_MODES)
32753 }
32754 TIME_ESTIMATE_TO_TARGET_DATA::ID => {
32755 TIME_ESTIMATE_TO_TARGET_DATA::deser(version, payload)
32756 .map(Self::TIME_ESTIMATE_TO_TARGET)
32757 }
32758 GPS_RAW_INT_DATA::ID => {
32759 GPS_RAW_INT_DATA::deser(version, payload).map(Self::GPS_RAW_INT)
32760 }
32761 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
32762 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::deser(version, payload)
32763 .map(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT)
32764 }
32765 VICON_POSITION_ESTIMATE_DATA::ID => {
32766 VICON_POSITION_ESTIMATE_DATA::deser(version, payload)
32767 .map(Self::VICON_POSITION_ESTIMATE)
32768 }
32769 SCALED_PRESSURE2_DATA::ID => {
32770 SCALED_PRESSURE2_DATA::deser(version, payload).map(Self::SCALED_PRESSURE2)
32771 }
32772 CONTROL_SYSTEM_STATE_DATA::ID => {
32773 CONTROL_SYSTEM_STATE_DATA::deser(version, payload).map(Self::CONTROL_SYSTEM_STATE)
32774 }
32775 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => {
32776 MISSION_REQUEST_PARTIAL_LIST_DATA::deser(version, payload)
32777 .map(Self::MISSION_REQUEST_PARTIAL_LIST)
32778 }
32779 HOME_POSITION_DATA::ID => {
32780 HOME_POSITION_DATA::deser(version, payload).map(Self::HOME_POSITION)
32781 }
32782 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => {
32783 CAMERA_TRACKING_IMAGE_STATUS_DATA::deser(version, payload)
32784 .map(Self::CAMERA_TRACKING_IMAGE_STATUS)
32785 }
32786 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::deser(version, payload)
32787 .map(Self::ACTUATOR_OUTPUT_STATUS),
32788 LOG_REQUEST_END_DATA::ID => {
32789 LOG_REQUEST_END_DATA::deser(version, payload).map(Self::LOG_REQUEST_END)
32790 }
32791 RC_CHANNELS_DATA::ID => {
32792 RC_CHANNELS_DATA::deser(version, payload).map(Self::RC_CHANNELS)
32793 }
32794 ATTITUDE_QUATERNION_COV_DATA::ID => {
32795 ATTITUDE_QUATERNION_COV_DATA::deser(version, payload)
32796 .map(Self::ATTITUDE_QUATERNION_COV)
32797 }
32798 CAMERA_TRIGGER_DATA::ID => {
32799 CAMERA_TRIGGER_DATA::deser(version, payload).map(Self::CAMERA_TRIGGER)
32800 }
32801 FOLLOW_TARGET_DATA::ID => {
32802 FOLLOW_TARGET_DATA::deser(version, payload).map(Self::FOLLOW_TARGET)
32803 }
32804 GLOBAL_POSITION_INT_COV_DATA::ID => {
32805 GLOBAL_POSITION_INT_COV_DATA::deser(version, payload)
32806 .map(Self::GLOBAL_POSITION_INT_COV)
32807 }
32808 MOUNT_ORIENTATION_DATA::ID => {
32809 MOUNT_ORIENTATION_DATA::deser(version, payload).map(Self::MOUNT_ORIENTATION)
32810 }
32811 GENERATOR_STATUS_DATA::ID => {
32812 GENERATOR_STATUS_DATA::deser(version, payload).map(Self::GENERATOR_STATUS)
32813 }
32814 GPS_RTCM_DATA_DATA::ID => {
32815 GPS_RTCM_DATA_DATA::deser(version, payload).map(Self::GPS_RTCM_DATA)
32816 }
32817 NAV_CONTROLLER_OUTPUT_DATA::ID => {
32818 NAV_CONTROLLER_OUTPUT_DATA::deser(version, payload).map(Self::NAV_CONTROLLER_OUTPUT)
32819 }
32820 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
32821 GLOBAL_VISION_POSITION_ESTIMATE_DATA::deser(version, payload)
32822 .map(Self::GLOBAL_VISION_POSITION_ESTIMATE)
32823 }
32824 PARAM_EXT_VALUE_DATA::ID => {
32825 PARAM_EXT_VALUE_DATA::deser(version, payload).map(Self::PARAM_EXT_VALUE)
32826 }
32827 CAMERA_CAPTURE_STATUS_DATA::ID => {
32828 CAMERA_CAPTURE_STATUS_DATA::deser(version, payload).map(Self::CAMERA_CAPTURE_STATUS)
32829 }
32830 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
32831 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::deser(version, payload)
32832 .map(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL)
32833 }
32834 GIMBAL_MANAGER_INFORMATION_DATA::ID => {
32835 GIMBAL_MANAGER_INFORMATION_DATA::deser(version, payload)
32836 .map(Self::GIMBAL_MANAGER_INFORMATION)
32837 }
32838 HIGH_LATENCY2_DATA::ID => {
32839 HIGH_LATENCY2_DATA::deser(version, payload).map(Self::HIGH_LATENCY2)
32840 }
32841 HIGHRES_IMU_DATA::ID => {
32842 HIGHRES_IMU_DATA::deser(version, payload).map(Self::HIGHRES_IMU)
32843 }
32844 HIL_CONTROLS_DATA::ID => {
32845 HIL_CONTROLS_DATA::deser(version, payload).map(Self::HIL_CONTROLS)
32846 }
32847 MISSION_REQUEST_DATA::ID => {
32848 MISSION_REQUEST_DATA::deser(version, payload).map(Self::MISSION_REQUEST)
32849 }
32850 LANDING_TARGET_DATA::ID => {
32851 LANDING_TARGET_DATA::deser(version, payload).map(Self::LANDING_TARGET)
32852 }
32853 LOG_REQUEST_LIST_DATA::ID => {
32854 LOG_REQUEST_LIST_DATA::deser(version, payload).map(Self::LOG_REQUEST_LIST)
32855 }
32856 CAMERA_FOV_STATUS_DATA::ID => {
32857 CAMERA_FOV_STATUS_DATA::deser(version, payload).map(Self::CAMERA_FOV_STATUS)
32858 }
32859 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::deser(version, payload).map(Self::LOG_ENTRY),
32860 GPS_INJECT_DATA_DATA::ID => {
32861 GPS_INJECT_DATA_DATA::deser(version, payload).map(Self::GPS_INJECT_DATA)
32862 }
32863 PARAM_VALUE_DATA::ID => {
32864 PARAM_VALUE_DATA::deser(version, payload).map(Self::PARAM_VALUE)
32865 }
32866 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => {
32867 GIMBAL_MANAGER_SET_PITCHYAW_DATA::deser(version, payload)
32868 .map(Self::GIMBAL_MANAGER_SET_PITCHYAW)
32869 }
32870 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::deser(version, payload)
32871 .map(Self::CURRENT_EVENT_SEQUENCE),
32872 CAMERA_INFORMATION_DATA::ID => {
32873 CAMERA_INFORMATION_DATA::deser(version, payload).map(Self::CAMERA_INFORMATION)
32874 }
32875 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => {
32876 OPEN_DRONE_ID_OPERATOR_ID_DATA::deser(version, payload)
32877 .map(Self::OPEN_DRONE_ID_OPERATOR_ID)
32878 }
32879 COMPONENT_INFORMATION_DATA::ID => {
32880 COMPONENT_INFORMATION_DATA::deser(version, payload).map(Self::COMPONENT_INFORMATION)
32881 }
32882 COMMAND_LONG_DATA::ID => {
32883 COMMAND_LONG_DATA::deser(version, payload).map(Self::COMMAND_LONG)
32884 }
32885 PARAM_EXT_SET_DATA::ID => {
32886 PARAM_EXT_SET_DATA::deser(version, payload).map(Self::PARAM_EXT_SET)
32887 }
32888 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::deser(version, payload).map(Self::GPS_INPUT),
32889 SET_MODE_DATA::ID => SET_MODE_DATA::deser(version, payload).map(Self::SET_MODE),
32890 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::deser(version, payload).map(Self::AIS_VESSEL),
32891 ATTITUDE_QUATERNION_DATA::ID => {
32892 ATTITUDE_QUATERNION_DATA::deser(version, payload).map(Self::ATTITUDE_QUATERNION)
32893 }
32894 CURRENT_MODE_DATA::ID => {
32895 CURRENT_MODE_DATA::deser(version, payload).map(Self::CURRENT_MODE)
32896 }
32897 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => {
32898 GIMBAL_DEVICE_SET_ATTITUDE_DATA::deser(version, payload)
32899 .map(Self::GIMBAL_DEVICE_SET_ATTITUDE)
32900 }
32901 HYGROMETER_SENSOR_DATA::ID => {
32902 HYGROMETER_SENSOR_DATA::deser(version, payload).map(Self::HYGROMETER_SENSOR)
32903 }
32904 PARAM_MAP_RC_DATA::ID => {
32905 PARAM_MAP_RC_DATA::deser(version, payload).map(Self::PARAM_MAP_RC)
32906 }
32907 COMPONENT_INFORMATION_BASIC_DATA::ID => {
32908 COMPONENT_INFORMATION_BASIC_DATA::deser(version, payload)
32909 .map(Self::COMPONENT_INFORMATION_BASIC)
32910 }
32911 OPEN_DRONE_ID_SYSTEM_DATA::ID => {
32912 OPEN_DRONE_ID_SYSTEM_DATA::deser(version, payload).map(Self::OPEN_DRONE_ID_SYSTEM)
32913 }
32914 COMMAND_ACK_DATA::ID => {
32915 COMMAND_ACK_DATA::deser(version, payload).map(Self::COMMAND_ACK)
32916 }
32917 SERIAL_CONTROL_DATA::ID => {
32918 SERIAL_CONTROL_DATA::deser(version, payload).map(Self::SERIAL_CONTROL)
32919 }
32920 _ => Err(::mavlink_core::error::ParserError::UnknownMessage { id }),
32921 }
32922 }
32923 fn message_name(&self) -> &'static str {
32924 match self {
32925 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::NAME,
32926 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::NAME,
32927 Self::SYS_STATUS(..) => SYS_STATUS_DATA::NAME,
32928 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::NAME,
32929 Self::TUNNEL(..) => TUNNEL_DATA::NAME,
32930 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::NAME,
32931 Self::RAW_IMU(..) => RAW_IMU_DATA::NAME,
32932 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::NAME,
32933 Self::HIL_STATE(..) => HIL_STATE_DATA::NAME,
32934 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::NAME,
32935 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
32936 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME
32937 }
32938 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
32939 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME
32940 }
32941 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::NAME,
32942 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::NAME,
32943 Self::GPS2_RAW(..) => GPS2_RAW_DATA::NAME,
32944 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::NAME,
32945 Self::HIL_GPS(..) => HIL_GPS_DATA::NAME,
32946 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::NAME,
32947 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::NAME,
32948 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::NAME,
32949 Self::EFI_STATUS(..) => EFI_STATUS_DATA::NAME,
32950 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::NAME,
32951 Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(..) => UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::NAME,
32952 Self::PING(..) => PING_DATA::NAME,
32953 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::NAME,
32954 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::NAME,
32955 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::NAME,
32956 Self::AUTH_KEY(..) => AUTH_KEY_DATA::NAME,
32957 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::NAME,
32958 Self::COLLISION(..) => COLLISION_DATA::NAME,
32959 Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(..) => {
32960 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::NAME
32961 }
32962 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::NAME,
32963 Self::UAVIONIX_ADSB_OUT_STATUS(..) => UAVIONIX_ADSB_OUT_STATUS_DATA::NAME,
32964 Self::MISSION_ACK(..) => MISSION_ACK_DATA::NAME,
32965 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::NAME,
32966 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::NAME,
32967 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::NAME,
32968 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::NAME,
32969 Self::DATA_STREAM(..) => DATA_STREAM_DATA::NAME,
32970 Self::PARAM_SET(..) => PARAM_SET_DATA::NAME,
32971 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::NAME,
32972 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::NAME,
32973 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::NAME,
32974 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::NAME,
32975 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::NAME,
32976 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::NAME,
32977 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::NAME,
32978 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::NAME,
32979 Self::DEBUG(..) => DEBUG_DATA::NAME,
32980 Self::CAN_FRAME(..) => CAN_FRAME_DATA::NAME,
32981 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::NAME,
32982 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::NAME,
32983 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::NAME,
32984 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::NAME,
32985 Self::LOG_DATA(..) => LOG_DATA_DATA::NAME,
32986 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::NAME,
32987 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::NAME,
32988 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::NAME,
32989 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::NAME,
32990 Self::UAVIONIX_ADSB_OUT_CONTROL(..) => UAVIONIX_ADSB_OUT_CONTROL_DATA::NAME,
32991 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::NAME,
32992 Self::HEARTBEAT(..) => HEARTBEAT_DATA::NAME,
32993 Self::EVENT(..) => EVENT_DATA::NAME,
32994 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::NAME,
32995 Self::COMMAND_INT(..) => COMMAND_INT_DATA::NAME,
32996 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::NAME,
32997 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::NAME,
32998 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::NAME,
32999 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::NAME,
33000 Self::WIND_COV(..) => WIND_COV_DATA::NAME,
33001 Self::ATTITUDE(..) => ATTITUDE_DATA::NAME,
33002 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::NAME,
33003 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::NAME,
33004 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::NAME,
33005 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::NAME,
33006 Self::GPS_STATUS(..) => GPS_STATUS_DATA::NAME,
33007 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::NAME,
33008 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME,
33009 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::NAME,
33010 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::NAME,
33011 Self::UAVIONIX_ADSB_OUT_DYNAMIC(..) => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::NAME,
33012 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::NAME,
33013 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::NAME,
33014 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::NAME,
33015 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::NAME,
33016 Self::SCALED_IMU(..) => SCALED_IMU_DATA::NAME,
33017 Self::STATUSTEXT(..) => STATUSTEXT_DATA::NAME,
33018 Self::ALTITUDE(..) => ALTITUDE_DATA::NAME,
33019 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::NAME,
33020 Self::RAW_RPM(..) => RAW_RPM_DATA::NAME,
33021 Self::GPS2_RTK(..) => GPS2_RTK_DATA::NAME,
33022 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::NAME,
33023 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::NAME,
33024 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::NAME,
33025 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::NAME,
33026 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::NAME,
33027 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::NAME,
33028 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::NAME,
33029 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::NAME,
33030 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::NAME,
33031 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::NAME,
33032 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::NAME,
33033 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::NAME,
33034 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME,
33035 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::NAME,
33036 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::NAME,
33037 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::NAME,
33038 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::NAME,
33039 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME,
33040 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::NAME,
33041 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::NAME,
33042 Self::VIBRATION(..) => VIBRATION_DATA::NAME,
33043 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::NAME,
33044 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::NAME,
33045 Self::POWER_STATUS(..) => POWER_STATUS_DATA::NAME,
33046 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::NAME,
33047 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME,
33048 Self::GPS_RTK(..) => GPS_RTK_DATA::NAME,
33049 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::NAME,
33050 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::NAME,
33051 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::NAME,
33052 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::NAME,
33053 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::NAME,
33054 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME,
33055 Self::ESC_INFO(..) => ESC_INFO_DATA::NAME,
33056 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::NAME,
33057 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::NAME,
33058 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::NAME,
33059 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::NAME,
33060 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::NAME,
33061 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::NAME,
33062 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::NAME,
33063 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::NAME,
33064 Self::TIMESYNC(..) => TIMESYNC_DATA::NAME,
33065 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME,
33066 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::NAME,
33067 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::NAME,
33068 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::NAME,
33069 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::NAME,
33070 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::NAME,
33071 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME,
33072 Self::ESC_STATUS(..) => ESC_STATUS_DATA::NAME,
33073 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::NAME,
33074 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::NAME,
33075 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::NAME,
33076 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::NAME,
33077 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::NAME,
33078 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::NAME,
33079 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::NAME,
33080 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::NAME,
33081 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::NAME,
33082 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::NAME,
33083 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::NAME,
33084 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::NAME,
33085 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::NAME,
33086 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::NAME,
33087 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::NAME,
33088 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::NAME,
33089 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::NAME,
33090 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::NAME,
33091 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::NAME,
33092 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::NAME,
33093 Self::LOG_ERASE(..) => LOG_ERASE_DATA::NAME,
33094 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::NAME,
33095 Self::UAVIONIX_ADSB_OUT_CFG(..) => UAVIONIX_ADSB_OUT_CFG_DATA::NAME,
33096 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => {
33097 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME
33098 }
33099 Self::SIM_STATE(..) => SIM_STATE_DATA::NAME,
33100 Self::ODOMETRY(..) => ODOMETRY_DATA::NAME,
33101 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::NAME,
33102 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::NAME,
33103 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::NAME,
33104 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
33105 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME
33106 }
33107 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::NAME,
33108 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::NAME,
33109 Self::UAVIONIX_ADSB_GET(..) => UAVIONIX_ADSB_GET_DATA::NAME,
33110 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::NAME,
33111 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::NAME,
33112 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::NAME,
33113 Self::VFR_HUD(..) => VFR_HUD_DATA::NAME,
33114 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::NAME,
33115 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::NAME,
33116 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::NAME,
33117 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::NAME,
33118 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::NAME,
33119 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::NAME,
33120 Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(..) => {
33121 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::NAME
33122 }
33123 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::NAME,
33124 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::NAME,
33125 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::NAME,
33126 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::NAME,
33127 Self::HOME_POSITION(..) => HOME_POSITION_DATA::NAME,
33128 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME,
33129 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::NAME,
33130 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::NAME,
33131 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::NAME,
33132 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::NAME,
33133 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::NAME,
33134 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::NAME,
33135 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::NAME,
33136 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::NAME,
33137 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::NAME,
33138 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::NAME,
33139 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::NAME,
33140 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME,
33141 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::NAME,
33142 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::NAME,
33143 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
33144 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME
33145 }
33146 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::NAME,
33147 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::NAME,
33148 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::NAME,
33149 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::NAME,
33150 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::NAME,
33151 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::NAME,
33152 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::NAME,
33153 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::NAME,
33154 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::NAME,
33155 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::NAME,
33156 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::NAME,
33157 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME,
33158 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::NAME,
33159 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::NAME,
33160 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME,
33161 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::NAME,
33162 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::NAME,
33163 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::NAME,
33164 Self::GPS_INPUT(..) => GPS_INPUT_DATA::NAME,
33165 Self::SET_MODE(..) => SET_MODE_DATA::NAME,
33166 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::NAME,
33167 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::NAME,
33168 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::NAME,
33169 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME,
33170 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::NAME,
33171 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::NAME,
33172 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::NAME,
33173 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::NAME,
33174 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::NAME,
33175 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::NAME,
33176 }
33177 }
33178 fn message_id(&self) -> u32 {
33179 match self {
33180 Self::MISSION_COUNT(..) => MISSION_COUNT_DATA::ID,
33181 Self::SYSTEM_TIME(..) => SYSTEM_TIME_DATA::ID,
33182 Self::SYS_STATUS(..) => SYS_STATUS_DATA::ID,
33183 Self::ADSB_VEHICLE(..) => ADSB_VEHICLE_DATA::ID,
33184 Self::TUNNEL(..) => TUNNEL_DATA::ID,
33185 Self::OPEN_DRONE_ID_ARM_STATUS(..) => OPEN_DRONE_ID_ARM_STATUS_DATA::ID,
33186 Self::RAW_IMU(..) => RAW_IMU_DATA::ID,
33187 Self::MISSION_CURRENT(..) => MISSION_CURRENT_DATA::ID,
33188 Self::HIL_STATE(..) => HIL_STATE_DATA::ID,
33189 Self::OBSTACLE_DISTANCE(..) => OBSTACLE_DISTANCE_DATA::ID,
33190 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(..) => {
33191 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID
33192 }
33193 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(..) => {
33194 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID
33195 }
33196 Self::CAMERA_IMAGE_CAPTURED(..) => CAMERA_IMAGE_CAPTURED_DATA::ID,
33197 Self::PROTOCOL_VERSION(..) => PROTOCOL_VERSION_DATA::ID,
33198 Self::GPS2_RAW(..) => GPS2_RAW_DATA::ID,
33199 Self::UTM_GLOBAL_POSITION(..) => UTM_GLOBAL_POSITION_DATA::ID,
33200 Self::HIL_GPS(..) => HIL_GPS_DATA::ID,
33201 Self::HIGH_LATENCY(..) => HIGH_LATENCY_DATA::ID,
33202 Self::OPEN_DRONE_ID_BASIC_ID(..) => OPEN_DRONE_ID_BASIC_ID_DATA::ID,
33203 Self::BATTERY_STATUS(..) => BATTERY_STATUS_DATA::ID,
33204 Self::EFI_STATUS(..) => EFI_STATUS_DATA::ID,
33205 Self::WINCH_STATUS(..) => WINCH_STATUS_DATA::ID,
33206 Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(..) => UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID,
33207 Self::PING(..) => PING_DATA::ID,
33208 Self::HIL_OPTICAL_FLOW(..) => HIL_OPTICAL_FLOW_DATA::ID,
33209 Self::VIDEO_STREAM_INFORMATION(..) => VIDEO_STREAM_INFORMATION_DATA::ID,
33210 Self::LOCAL_POSITION_NED_COV(..) => LOCAL_POSITION_NED_COV_DATA::ID,
33211 Self::AUTH_KEY(..) => AUTH_KEY_DATA::ID,
33212 Self::HIL_ACTUATOR_CONTROLS(..) => HIL_ACTUATOR_CONTROLS_DATA::ID,
33213 Self::COLLISION(..) => COLLISION_DATA::ID,
33214 Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(..) => {
33215 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID
33216 }
33217 Self::HIL_STATE_QUATERNION(..) => HIL_STATE_QUATERNION_DATA::ID,
33218 Self::UAVIONIX_ADSB_OUT_STATUS(..) => UAVIONIX_ADSB_OUT_STATUS_DATA::ID,
33219 Self::MISSION_ACK(..) => MISSION_ACK_DATA::ID,
33220 Self::WHEEL_DISTANCE(..) => WHEEL_DISTANCE_DATA::ID,
33221 Self::OPTICAL_FLOW_RAD(..) => OPTICAL_FLOW_RAD_DATA::ID,
33222 Self::CAMERA_TRACKING_GEO_STATUS(..) => CAMERA_TRACKING_GEO_STATUS_DATA::ID,
33223 Self::CELLULAR_CONFIG(..) => CELLULAR_CONFIG_DATA::ID,
33224 Self::DATA_STREAM(..) => DATA_STREAM_DATA::ID,
33225 Self::PARAM_SET(..) => PARAM_SET_DATA::ID,
33226 Self::UAVCAN_NODE_STATUS(..) => UAVCAN_NODE_STATUS_DATA::ID,
33227 Self::STORAGE_INFORMATION(..) => STORAGE_INFORMATION_DATA::ID,
33228 Self::MISSION_REQUEST_INT(..) => MISSION_REQUEST_INT_DATA::ID,
33229 Self::SCALED_PRESSURE(..) => SCALED_PRESSURE_DATA::ID,
33230 Self::ENCAPSULATED_DATA(..) => ENCAPSULATED_DATA_DATA::ID,
33231 Self::PLAY_TUNE(..) => PLAY_TUNE_DATA::ID,
33232 Self::CANFD_FRAME(..) => CANFD_FRAME_DATA::ID,
33233 Self::AVAILABLE_MODES_MONITOR(..) => AVAILABLE_MODES_MONITOR_DATA::ID,
33234 Self::DEBUG(..) => DEBUG_DATA::ID,
33235 Self::CAN_FRAME(..) => CAN_FRAME_DATA::ID,
33236 Self::MANUAL_SETPOINT(..) => MANUAL_SETPOINT_DATA::ID,
33237 Self::MISSION_SET_CURRENT(..) => MISSION_SET_CURRENT_DATA::ID,
33238 Self::BUTTON_CHANGE(..) => BUTTON_CHANGE_DATA::ID,
33239 Self::CAN_FILTER_MODIFY(..) => CAN_FILTER_MODIFY_DATA::ID,
33240 Self::LOG_DATA(..) => LOG_DATA_DATA::ID,
33241 Self::DEBUG_VECT(..) => DEBUG_VECT_DATA::ID,
33242 Self::PLAY_TUNE_V2(..) => PLAY_TUNE_V2_DATA::ID,
33243 Self::OPEN_DRONE_ID_SELF_ID(..) => OPEN_DRONE_ID_SELF_ID_DATA::ID,
33244 Self::COMMAND_CANCEL(..) => COMMAND_CANCEL_DATA::ID,
33245 Self::UAVIONIX_ADSB_OUT_CONTROL(..) => UAVIONIX_ADSB_OUT_CONTROL_DATA::ID,
33246 Self::RESPONSE_EVENT_ERROR(..) => RESPONSE_EVENT_ERROR_DATA::ID,
33247 Self::HEARTBEAT(..) => HEARTBEAT_DATA::ID,
33248 Self::EVENT(..) => EVENT_DATA::ID,
33249 Self::DEBUG_FLOAT_ARRAY(..) => DEBUG_FLOAT_ARRAY_DATA::ID,
33250 Self::COMMAND_INT(..) => COMMAND_INT_DATA::ID,
33251 Self::FILE_TRANSFER_PROTOCOL(..) => FILE_TRANSFER_PROTOCOL_DATA::ID,
33252 Self::CELLULAR_STATUS(..) => CELLULAR_STATUS_DATA::ID,
33253 Self::REQUEST_DATA_STREAM(..) => REQUEST_DATA_STREAM_DATA::ID,
33254 Self::PARAM_EXT_REQUEST_LIST(..) => PARAM_EXT_REQUEST_LIST_DATA::ID,
33255 Self::WIND_COV(..) => WIND_COV_DATA::ID,
33256 Self::ATTITUDE(..) => ATTITUDE_DATA::ID,
33257 Self::RADIO_STATUS(..) => RADIO_STATUS_DATA::ID,
33258 Self::NAMED_VALUE_FLOAT(..) => NAMED_VALUE_FLOAT_DATA::ID,
33259 Self::GPS_GLOBAL_ORIGIN(..) => GPS_GLOBAL_ORIGIN_DATA::ID,
33260 Self::POSITION_TARGET_GLOBAL_INT(..) => POSITION_TARGET_GLOBAL_INT_DATA::ID,
33261 Self::GPS_STATUS(..) => GPS_STATUS_DATA::ID,
33262 Self::PARAM_REQUEST_LIST(..) => PARAM_REQUEST_LIST_DATA::ID,
33263 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(..) => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID,
33264 Self::FUEL_STATUS(..) => FUEL_STATUS_DATA::ID,
33265 Self::MEMORY_VECT(..) => MEMORY_VECT_DATA::ID,
33266 Self::UAVIONIX_ADSB_OUT_DYNAMIC(..) => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID,
33267 Self::CAMERA_SETTINGS(..) => CAMERA_SETTINGS_DATA::ID,
33268 Self::SERVO_OUTPUT_RAW(..) => SERVO_OUTPUT_RAW_DATA::ID,
33269 Self::ACTUATOR_CONTROL_TARGET(..) => ACTUATOR_CONTROL_TARGET_DATA::ID,
33270 Self::ATTITUDE_TARGET(..) => ATTITUDE_TARGET_DATA::ID,
33271 Self::SCALED_IMU(..) => SCALED_IMU_DATA::ID,
33272 Self::STATUSTEXT(..) => STATUSTEXT_DATA::ID,
33273 Self::ALTITUDE(..) => ALTITUDE_DATA::ID,
33274 Self::CHANGE_OPERATOR_CONTROL(..) => CHANGE_OPERATOR_CONTROL_DATA::ID,
33275 Self::RAW_RPM(..) => RAW_RPM_DATA::ID,
33276 Self::GPS2_RTK(..) => GPS2_RTK_DATA::ID,
33277 Self::OPTICAL_FLOW(..) => OPTICAL_FLOW_DATA::ID,
33278 Self::TERRAIN_DATA(..) => TERRAIN_DATA_DATA::ID,
33279 Self::ORBIT_EXECUTION_STATUS(..) => ORBIT_EXECUTION_STATUS_DATA::ID,
33280 Self::GLOBAL_POSITION_INT(..) => GLOBAL_POSITION_INT_DATA::ID,
33281 Self::TERRAIN_REPORT(..) => TERRAIN_REPORT_DATA::ID,
33282 Self::SAFETY_SET_ALLOWED_AREA(..) => SAFETY_SET_ALLOWED_AREA_DATA::ID,
33283 Self::SET_HOME_POSITION(..) => SET_HOME_POSITION_DATA::ID,
33284 Self::AUTOPILOT_VERSION(..) => AUTOPILOT_VERSION_DATA::ID,
33285 Self::SETUP_SIGNING(..) => SETUP_SIGNING_DATA::ID,
33286 Self::ILLUMINATOR_STATUS(..) => ILLUMINATOR_STATUS_DATA::ID,
33287 Self::UAVCAN_NODE_INFO(..) => UAVCAN_NODE_INFO_DATA::ID,
33288 Self::GIMBAL_DEVICE_INFORMATION(..) => GIMBAL_DEVICE_INFORMATION_DATA::ID,
33289 Self::GIMBAL_MANAGER_SET_ATTITUDE(..) => GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID,
33290 Self::LOGGING_DATA_ACKED(..) => LOGGING_DATA_ACKED_DATA::ID,
33291 Self::RC_CHANNELS_RAW(..) => RC_CHANNELS_RAW_DATA::ID,
33292 Self::LINK_NODE_STATUS(..) => LINK_NODE_STATUS_DATA::ID,
33293 Self::MISSION_ITEM_REACHED(..) => MISSION_ITEM_REACHED_DATA::ID,
33294 Self::SET_POSITION_TARGET_GLOBAL_INT(..) => SET_POSITION_TARGET_GLOBAL_INT_DATA::ID,
33295 Self::SMART_BATTERY_INFO(..) => SMART_BATTERY_INFO_DATA::ID,
33296 Self::SET_GPS_GLOBAL_ORIGIN(..) => SET_GPS_GLOBAL_ORIGIN_DATA::ID,
33297 Self::VIBRATION(..) => VIBRATION_DATA::ID,
33298 Self::GIMBAL_MANAGER_STATUS(..) => GIMBAL_MANAGER_STATUS_DATA::ID,
33299 Self::MISSION_ITEM_INT(..) => MISSION_ITEM_INT_DATA::ID,
33300 Self::POWER_STATUS(..) => POWER_STATUS_DATA::ID,
33301 Self::LOGGING_DATA(..) => LOGGING_DATA_DATA::ID,
33302 Self::CHANGE_OPERATOR_CONTROL_ACK(..) => CHANGE_OPERATOR_CONTROL_ACK_DATA::ID,
33303 Self::GPS_RTK(..) => GPS_RTK_DATA::ID,
33304 Self::FLIGHT_INFORMATION(..) => FLIGHT_INFORMATION_DATA::ID,
33305 Self::SUPPORTED_TUNES(..) => SUPPORTED_TUNES_DATA::ID,
33306 Self::WIFI_CONFIG_AP(..) => WIFI_CONFIG_AP_DATA::ID,
33307 Self::TERRAIN_CHECK(..) => TERRAIN_CHECK_DATA::ID,
33308 Self::RAW_PRESSURE(..) => RAW_PRESSURE_DATA::ID,
33309 Self::OPEN_DRONE_ID_AUTHENTICATION(..) => OPEN_DRONE_ID_AUTHENTICATION_DATA::ID,
33310 Self::ESC_INFO(..) => ESC_INFO_DATA::ID,
33311 Self::DISTANCE_SENSOR(..) => DISTANCE_SENSOR_DATA::ID,
33312 Self::HIL_RC_INPUTS_RAW(..) => HIL_RC_INPUTS_RAW_DATA::ID,
33313 Self::ISBD_LINK_STATUS(..) => ISBD_LINK_STATUS_DATA::ID,
33314 Self::RC_CHANNELS_SCALED(..) => RC_CHANNELS_SCALED_DATA::ID,
33315 Self::SCALED_IMU2(..) => SCALED_IMU2_DATA::ID,
33316 Self::HIL_SENSOR(..) => HIL_SENSOR_DATA::ID,
33317 Self::RESOURCE_REQUEST(..) => RESOURCE_REQUEST_DATA::ID,
33318 Self::CAMERA_THERMAL_RANGE(..) => CAMERA_THERMAL_RANGE_DATA::ID,
33319 Self::TIMESYNC(..) => TIMESYNC_DATA::ID,
33320 Self::OPEN_DRONE_ID_MESSAGE_PACK(..) => OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID,
33321 Self::LOG_REQUEST_DATA(..) => LOG_REQUEST_DATA_DATA::ID,
33322 Self::COMPONENT_METADATA(..) => COMPONENT_METADATA_DATA::ID,
33323 Self::MAG_CAL_REPORT(..) => MAG_CAL_REPORT_DATA::ID,
33324 Self::NAMED_VALUE_INT(..) => NAMED_VALUE_INT_DATA::ID,
33325 Self::SAFETY_ALLOWED_AREA(..) => SAFETY_ALLOWED_AREA_DATA::ID,
33326 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(..) => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID,
33327 Self::ESC_STATUS(..) => ESC_STATUS_DATA::ID,
33328 Self::PARAM_EXT_REQUEST_READ(..) => PARAM_EXT_REQUEST_READ_DATA::ID,
33329 Self::SCALED_IMU3(..) => SCALED_IMU3_DATA::ID,
33330 Self::ESTIMATOR_STATUS(..) => ESTIMATOR_STATUS_DATA::ID,
33331 Self::PARAM_EXT_ACK(..) => PARAM_EXT_ACK_DATA::ID,
33332 Self::V2_EXTENSION(..) => V2_EXTENSION_DATA::ID,
33333 Self::SET_ACTUATOR_CONTROL_TARGET(..) => SET_ACTUATOR_CONTROL_TARGET_DATA::ID,
33334 Self::RC_CHANNELS_OVERRIDE(..) => RC_CHANNELS_OVERRIDE_DATA::ID,
33335 Self::DATA_TRANSMISSION_HANDSHAKE(..) => DATA_TRANSMISSION_HANDSHAKE_DATA::ID,
33336 Self::LOCAL_POSITION_NED(..) => LOCAL_POSITION_NED_DATA::ID,
33337 Self::EXTENDED_SYS_STATE(..) => EXTENDED_SYS_STATE_DATA::ID,
33338 Self::FENCE_STATUS(..) => FENCE_STATUS_DATA::ID,
33339 Self::ONBOARD_COMPUTER_STATUS(..) => ONBOARD_COMPUTER_STATUS_DATA::ID,
33340 Self::MISSION_REQUEST_LIST(..) => MISSION_REQUEST_LIST_DATA::ID,
33341 Self::MESSAGE_INTERVAL(..) => MESSAGE_INTERVAL_DATA::ID,
33342 Self::TERRAIN_REQUEST(..) => TERRAIN_REQUEST_DATA::ID,
33343 Self::SCALED_PRESSURE3(..) => SCALED_PRESSURE3_DATA::ID,
33344 Self::REQUEST_EVENT(..) => REQUEST_EVENT_DATA::ID,
33345 Self::SET_ATTITUDE_TARGET(..) => SET_ATTITUDE_TARGET_DATA::ID,
33346 Self::SET_POSITION_TARGET_LOCAL_NED(..) => SET_POSITION_TARGET_LOCAL_NED_DATA::ID,
33347 Self::LOGGING_ACK(..) => LOGGING_ACK_DATA::ID,
33348 Self::LOG_ERASE(..) => LOG_ERASE_DATA::ID,
33349 Self::OPEN_DRONE_ID_LOCATION(..) => OPEN_DRONE_ID_LOCATION_DATA::ID,
33350 Self::UAVIONIX_ADSB_OUT_CFG(..) => UAVIONIX_ADSB_OUT_CFG_DATA::ID,
33351 Self::TRAJECTORY_REPRESENTATION_BEZIER(..) => TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID,
33352 Self::SIM_STATE(..) => SIM_STATE_DATA::ID,
33353 Self::ODOMETRY(..) => ODOMETRY_DATA::ID,
33354 Self::VISION_POSITION_ESTIMATE(..) => VISION_POSITION_ESTIMATE_DATA::ID,
33355 Self::PARAM_REQUEST_READ(..) => PARAM_REQUEST_READ_DATA::ID,
33356 Self::BATTERY_INFO(..) => BATTERY_INFO_DATA::ID,
33357 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(..) => {
33358 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID
33359 }
33360 Self::VIDEO_STREAM_STATUS(..) => VIDEO_STREAM_STATUS_DATA::ID,
33361 Self::ATT_POS_MOCAP(..) => ATT_POS_MOCAP_DATA::ID,
33362 Self::UAVIONIX_ADSB_GET(..) => UAVIONIX_ADSB_GET_DATA::ID,
33363 Self::MISSION_ITEM(..) => MISSION_ITEM_DATA::ID,
33364 Self::VISION_SPEED_ESTIMATE(..) => VISION_SPEED_ESTIMATE_DATA::ID,
33365 Self::MISSION_WRITE_PARTIAL_LIST(..) => MISSION_WRITE_PARTIAL_LIST_DATA::ID,
33366 Self::VFR_HUD(..) => VFR_HUD_DATA::ID,
33367 Self::POSITION_TARGET_LOCAL_NED(..) => POSITION_TARGET_LOCAL_NED_DATA::ID,
33368 Self::MISSION_CLEAR_ALL(..) => MISSION_CLEAR_ALL_DATA::ID,
33369 Self::MANUAL_CONTROL(..) => MANUAL_CONTROL_DATA::ID,
33370 Self::AVAILABLE_MODES(..) => AVAILABLE_MODES_DATA::ID,
33371 Self::TIME_ESTIMATE_TO_TARGET(..) => TIME_ESTIMATE_TO_TARGET_DATA::ID,
33372 Self::GPS_RAW_INT(..) => GPS_RAW_INT_DATA::ID,
33373 Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(..) => {
33374 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID
33375 }
33376 Self::VICON_POSITION_ESTIMATE(..) => VICON_POSITION_ESTIMATE_DATA::ID,
33377 Self::SCALED_PRESSURE2(..) => SCALED_PRESSURE2_DATA::ID,
33378 Self::CONTROL_SYSTEM_STATE(..) => CONTROL_SYSTEM_STATE_DATA::ID,
33379 Self::MISSION_REQUEST_PARTIAL_LIST(..) => MISSION_REQUEST_PARTIAL_LIST_DATA::ID,
33380 Self::HOME_POSITION(..) => HOME_POSITION_DATA::ID,
33381 Self::CAMERA_TRACKING_IMAGE_STATUS(..) => CAMERA_TRACKING_IMAGE_STATUS_DATA::ID,
33382 Self::ACTUATOR_OUTPUT_STATUS(..) => ACTUATOR_OUTPUT_STATUS_DATA::ID,
33383 Self::LOG_REQUEST_END(..) => LOG_REQUEST_END_DATA::ID,
33384 Self::RC_CHANNELS(..) => RC_CHANNELS_DATA::ID,
33385 Self::ATTITUDE_QUATERNION_COV(..) => ATTITUDE_QUATERNION_COV_DATA::ID,
33386 Self::CAMERA_TRIGGER(..) => CAMERA_TRIGGER_DATA::ID,
33387 Self::FOLLOW_TARGET(..) => FOLLOW_TARGET_DATA::ID,
33388 Self::GLOBAL_POSITION_INT_COV(..) => GLOBAL_POSITION_INT_COV_DATA::ID,
33389 Self::MOUNT_ORIENTATION(..) => MOUNT_ORIENTATION_DATA::ID,
33390 Self::GENERATOR_STATUS(..) => GENERATOR_STATUS_DATA::ID,
33391 Self::GPS_RTCM_DATA(..) => GPS_RTCM_DATA_DATA::ID,
33392 Self::NAV_CONTROLLER_OUTPUT(..) => NAV_CONTROLLER_OUTPUT_DATA::ID,
33393 Self::GLOBAL_VISION_POSITION_ESTIMATE(..) => GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID,
33394 Self::PARAM_EXT_VALUE(..) => PARAM_EXT_VALUE_DATA::ID,
33395 Self::CAMERA_CAPTURE_STATUS(..) => CAMERA_CAPTURE_STATUS_DATA::ID,
33396 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(..) => {
33397 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID
33398 }
33399 Self::GIMBAL_MANAGER_INFORMATION(..) => GIMBAL_MANAGER_INFORMATION_DATA::ID,
33400 Self::HIGH_LATENCY2(..) => HIGH_LATENCY2_DATA::ID,
33401 Self::HIGHRES_IMU(..) => HIGHRES_IMU_DATA::ID,
33402 Self::HIL_CONTROLS(..) => HIL_CONTROLS_DATA::ID,
33403 Self::MISSION_REQUEST(..) => MISSION_REQUEST_DATA::ID,
33404 Self::LANDING_TARGET(..) => LANDING_TARGET_DATA::ID,
33405 Self::LOG_REQUEST_LIST(..) => LOG_REQUEST_LIST_DATA::ID,
33406 Self::CAMERA_FOV_STATUS(..) => CAMERA_FOV_STATUS_DATA::ID,
33407 Self::LOG_ENTRY(..) => LOG_ENTRY_DATA::ID,
33408 Self::GPS_INJECT_DATA(..) => GPS_INJECT_DATA_DATA::ID,
33409 Self::PARAM_VALUE(..) => PARAM_VALUE_DATA::ID,
33410 Self::GIMBAL_MANAGER_SET_PITCHYAW(..) => GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID,
33411 Self::CURRENT_EVENT_SEQUENCE(..) => CURRENT_EVENT_SEQUENCE_DATA::ID,
33412 Self::CAMERA_INFORMATION(..) => CAMERA_INFORMATION_DATA::ID,
33413 Self::OPEN_DRONE_ID_OPERATOR_ID(..) => OPEN_DRONE_ID_OPERATOR_ID_DATA::ID,
33414 Self::COMPONENT_INFORMATION(..) => COMPONENT_INFORMATION_DATA::ID,
33415 Self::COMMAND_LONG(..) => COMMAND_LONG_DATA::ID,
33416 Self::PARAM_EXT_SET(..) => PARAM_EXT_SET_DATA::ID,
33417 Self::GPS_INPUT(..) => GPS_INPUT_DATA::ID,
33418 Self::SET_MODE(..) => SET_MODE_DATA::ID,
33419 Self::AIS_VESSEL(..) => AIS_VESSEL_DATA::ID,
33420 Self::ATTITUDE_QUATERNION(..) => ATTITUDE_QUATERNION_DATA::ID,
33421 Self::CURRENT_MODE(..) => CURRENT_MODE_DATA::ID,
33422 Self::GIMBAL_DEVICE_SET_ATTITUDE(..) => GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID,
33423 Self::HYGROMETER_SENSOR(..) => HYGROMETER_SENSOR_DATA::ID,
33424 Self::PARAM_MAP_RC(..) => PARAM_MAP_RC_DATA::ID,
33425 Self::COMPONENT_INFORMATION_BASIC(..) => COMPONENT_INFORMATION_BASIC_DATA::ID,
33426 Self::OPEN_DRONE_ID_SYSTEM(..) => OPEN_DRONE_ID_SYSTEM_DATA::ID,
33427 Self::COMMAND_ACK(..) => COMMAND_ACK_DATA::ID,
33428 Self::SERIAL_CONTROL(..) => SERIAL_CONTROL_DATA::ID,
33429 }
33430 }
33431 fn message_id_from_name(name: &str) -> Option<u32> {
33432 match name {
33433 MISSION_COUNT_DATA::NAME => Some(MISSION_COUNT_DATA::ID),
33434 SYSTEM_TIME_DATA::NAME => Some(SYSTEM_TIME_DATA::ID),
33435 SYS_STATUS_DATA::NAME => Some(SYS_STATUS_DATA::ID),
33436 ADSB_VEHICLE_DATA::NAME => Some(ADSB_VEHICLE_DATA::ID),
33437 TUNNEL_DATA::NAME => Some(TUNNEL_DATA::ID),
33438 OPEN_DRONE_ID_ARM_STATUS_DATA::NAME => Some(OPEN_DRONE_ID_ARM_STATUS_DATA::ID),
33439 RAW_IMU_DATA::NAME => Some(RAW_IMU_DATA::ID),
33440 MISSION_CURRENT_DATA::NAME => Some(MISSION_CURRENT_DATA::ID),
33441 HIL_STATE_DATA::NAME => Some(HIL_STATE_DATA::ID),
33442 OBSTACLE_DISTANCE_DATA::NAME => Some(OBSTACLE_DISTANCE_DATA::ID),
33443 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::NAME => {
33444 Some(TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID)
33445 }
33446 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::NAME => {
33447 Some(AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID)
33448 }
33449 CAMERA_IMAGE_CAPTURED_DATA::NAME => Some(CAMERA_IMAGE_CAPTURED_DATA::ID),
33450 PROTOCOL_VERSION_DATA::NAME => Some(PROTOCOL_VERSION_DATA::ID),
33451 GPS2_RAW_DATA::NAME => Some(GPS2_RAW_DATA::ID),
33452 UTM_GLOBAL_POSITION_DATA::NAME => Some(UTM_GLOBAL_POSITION_DATA::ID),
33453 HIL_GPS_DATA::NAME => Some(HIL_GPS_DATA::ID),
33454 HIGH_LATENCY_DATA::NAME => Some(HIGH_LATENCY_DATA::ID),
33455 OPEN_DRONE_ID_BASIC_ID_DATA::NAME => Some(OPEN_DRONE_ID_BASIC_ID_DATA::ID),
33456 BATTERY_STATUS_DATA::NAME => Some(BATTERY_STATUS_DATA::ID),
33457 EFI_STATUS_DATA::NAME => Some(EFI_STATUS_DATA::ID),
33458 WINCH_STATUS_DATA::NAME => Some(WINCH_STATUS_DATA::ID),
33459 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::NAME => {
33460 Some(UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID)
33461 }
33462 PING_DATA::NAME => Some(PING_DATA::ID),
33463 HIL_OPTICAL_FLOW_DATA::NAME => Some(HIL_OPTICAL_FLOW_DATA::ID),
33464 VIDEO_STREAM_INFORMATION_DATA::NAME => Some(VIDEO_STREAM_INFORMATION_DATA::ID),
33465 LOCAL_POSITION_NED_COV_DATA::NAME => Some(LOCAL_POSITION_NED_COV_DATA::ID),
33466 AUTH_KEY_DATA::NAME => Some(AUTH_KEY_DATA::ID),
33467 HIL_ACTUATOR_CONTROLS_DATA::NAME => Some(HIL_ACTUATOR_CONTROLS_DATA::ID),
33468 COLLISION_DATA::NAME => Some(COLLISION_DATA::ID),
33469 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::NAME => {
33470 Some(UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID)
33471 }
33472 HIL_STATE_QUATERNION_DATA::NAME => Some(HIL_STATE_QUATERNION_DATA::ID),
33473 UAVIONIX_ADSB_OUT_STATUS_DATA::NAME => Some(UAVIONIX_ADSB_OUT_STATUS_DATA::ID),
33474 MISSION_ACK_DATA::NAME => Some(MISSION_ACK_DATA::ID),
33475 WHEEL_DISTANCE_DATA::NAME => Some(WHEEL_DISTANCE_DATA::ID),
33476 OPTICAL_FLOW_RAD_DATA::NAME => Some(OPTICAL_FLOW_RAD_DATA::ID),
33477 CAMERA_TRACKING_GEO_STATUS_DATA::NAME => Some(CAMERA_TRACKING_GEO_STATUS_DATA::ID),
33478 CELLULAR_CONFIG_DATA::NAME => Some(CELLULAR_CONFIG_DATA::ID),
33479 DATA_STREAM_DATA::NAME => Some(DATA_STREAM_DATA::ID),
33480 PARAM_SET_DATA::NAME => Some(PARAM_SET_DATA::ID),
33481 UAVCAN_NODE_STATUS_DATA::NAME => Some(UAVCAN_NODE_STATUS_DATA::ID),
33482 STORAGE_INFORMATION_DATA::NAME => Some(STORAGE_INFORMATION_DATA::ID),
33483 MISSION_REQUEST_INT_DATA::NAME => Some(MISSION_REQUEST_INT_DATA::ID),
33484 SCALED_PRESSURE_DATA::NAME => Some(SCALED_PRESSURE_DATA::ID),
33485 ENCAPSULATED_DATA_DATA::NAME => Some(ENCAPSULATED_DATA_DATA::ID),
33486 PLAY_TUNE_DATA::NAME => Some(PLAY_TUNE_DATA::ID),
33487 CANFD_FRAME_DATA::NAME => Some(CANFD_FRAME_DATA::ID),
33488 AVAILABLE_MODES_MONITOR_DATA::NAME => Some(AVAILABLE_MODES_MONITOR_DATA::ID),
33489 DEBUG_DATA::NAME => Some(DEBUG_DATA::ID),
33490 CAN_FRAME_DATA::NAME => Some(CAN_FRAME_DATA::ID),
33491 MANUAL_SETPOINT_DATA::NAME => Some(MANUAL_SETPOINT_DATA::ID),
33492 MISSION_SET_CURRENT_DATA::NAME => Some(MISSION_SET_CURRENT_DATA::ID),
33493 BUTTON_CHANGE_DATA::NAME => Some(BUTTON_CHANGE_DATA::ID),
33494 CAN_FILTER_MODIFY_DATA::NAME => Some(CAN_FILTER_MODIFY_DATA::ID),
33495 LOG_DATA_DATA::NAME => Some(LOG_DATA_DATA::ID),
33496 DEBUG_VECT_DATA::NAME => Some(DEBUG_VECT_DATA::ID),
33497 PLAY_TUNE_V2_DATA::NAME => Some(PLAY_TUNE_V2_DATA::ID),
33498 OPEN_DRONE_ID_SELF_ID_DATA::NAME => Some(OPEN_DRONE_ID_SELF_ID_DATA::ID),
33499 COMMAND_CANCEL_DATA::NAME => Some(COMMAND_CANCEL_DATA::ID),
33500 UAVIONIX_ADSB_OUT_CONTROL_DATA::NAME => Some(UAVIONIX_ADSB_OUT_CONTROL_DATA::ID),
33501 RESPONSE_EVENT_ERROR_DATA::NAME => Some(RESPONSE_EVENT_ERROR_DATA::ID),
33502 HEARTBEAT_DATA::NAME => Some(HEARTBEAT_DATA::ID),
33503 EVENT_DATA::NAME => Some(EVENT_DATA::ID),
33504 DEBUG_FLOAT_ARRAY_DATA::NAME => Some(DEBUG_FLOAT_ARRAY_DATA::ID),
33505 COMMAND_INT_DATA::NAME => Some(COMMAND_INT_DATA::ID),
33506 FILE_TRANSFER_PROTOCOL_DATA::NAME => Some(FILE_TRANSFER_PROTOCOL_DATA::ID),
33507 CELLULAR_STATUS_DATA::NAME => Some(CELLULAR_STATUS_DATA::ID),
33508 REQUEST_DATA_STREAM_DATA::NAME => Some(REQUEST_DATA_STREAM_DATA::ID),
33509 PARAM_EXT_REQUEST_LIST_DATA::NAME => Some(PARAM_EXT_REQUEST_LIST_DATA::ID),
33510 WIND_COV_DATA::NAME => Some(WIND_COV_DATA::ID),
33511 ATTITUDE_DATA::NAME => Some(ATTITUDE_DATA::ID),
33512 RADIO_STATUS_DATA::NAME => Some(RADIO_STATUS_DATA::ID),
33513 NAMED_VALUE_FLOAT_DATA::NAME => Some(NAMED_VALUE_FLOAT_DATA::ID),
33514 GPS_GLOBAL_ORIGIN_DATA::NAME => Some(GPS_GLOBAL_ORIGIN_DATA::ID),
33515 POSITION_TARGET_GLOBAL_INT_DATA::NAME => Some(POSITION_TARGET_GLOBAL_INT_DATA::ID),
33516 GPS_STATUS_DATA::NAME => Some(GPS_STATUS_DATA::ID),
33517 PARAM_REQUEST_LIST_DATA::NAME => Some(PARAM_REQUEST_LIST_DATA::ID),
33518 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID),
33519 FUEL_STATUS_DATA::NAME => Some(FUEL_STATUS_DATA::ID),
33520 MEMORY_VECT_DATA::NAME => Some(MEMORY_VECT_DATA::ID),
33521 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::NAME => Some(UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID),
33522 CAMERA_SETTINGS_DATA::NAME => Some(CAMERA_SETTINGS_DATA::ID),
33523 SERVO_OUTPUT_RAW_DATA::NAME => Some(SERVO_OUTPUT_RAW_DATA::ID),
33524 ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(ACTUATOR_CONTROL_TARGET_DATA::ID),
33525 ATTITUDE_TARGET_DATA::NAME => Some(ATTITUDE_TARGET_DATA::ID),
33526 SCALED_IMU_DATA::NAME => Some(SCALED_IMU_DATA::ID),
33527 STATUSTEXT_DATA::NAME => Some(STATUSTEXT_DATA::ID),
33528 ALTITUDE_DATA::NAME => Some(ALTITUDE_DATA::ID),
33529 CHANGE_OPERATOR_CONTROL_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_DATA::ID),
33530 RAW_RPM_DATA::NAME => Some(RAW_RPM_DATA::ID),
33531 GPS2_RTK_DATA::NAME => Some(GPS2_RTK_DATA::ID),
33532 OPTICAL_FLOW_DATA::NAME => Some(OPTICAL_FLOW_DATA::ID),
33533 TERRAIN_DATA_DATA::NAME => Some(TERRAIN_DATA_DATA::ID),
33534 ORBIT_EXECUTION_STATUS_DATA::NAME => Some(ORBIT_EXECUTION_STATUS_DATA::ID),
33535 GLOBAL_POSITION_INT_DATA::NAME => Some(GLOBAL_POSITION_INT_DATA::ID),
33536 TERRAIN_REPORT_DATA::NAME => Some(TERRAIN_REPORT_DATA::ID),
33537 SAFETY_SET_ALLOWED_AREA_DATA::NAME => Some(SAFETY_SET_ALLOWED_AREA_DATA::ID),
33538 SET_HOME_POSITION_DATA::NAME => Some(SET_HOME_POSITION_DATA::ID),
33539 AUTOPILOT_VERSION_DATA::NAME => Some(AUTOPILOT_VERSION_DATA::ID),
33540 SETUP_SIGNING_DATA::NAME => Some(SETUP_SIGNING_DATA::ID),
33541 ILLUMINATOR_STATUS_DATA::NAME => Some(ILLUMINATOR_STATUS_DATA::ID),
33542 UAVCAN_NODE_INFO_DATA::NAME => Some(UAVCAN_NODE_INFO_DATA::ID),
33543 GIMBAL_DEVICE_INFORMATION_DATA::NAME => Some(GIMBAL_DEVICE_INFORMATION_DATA::ID),
33544 GIMBAL_MANAGER_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID),
33545 LOGGING_DATA_ACKED_DATA::NAME => Some(LOGGING_DATA_ACKED_DATA::ID),
33546 RC_CHANNELS_RAW_DATA::NAME => Some(RC_CHANNELS_RAW_DATA::ID),
33547 LINK_NODE_STATUS_DATA::NAME => Some(LINK_NODE_STATUS_DATA::ID),
33548 MISSION_ITEM_REACHED_DATA::NAME => Some(MISSION_ITEM_REACHED_DATA::ID),
33549 SET_POSITION_TARGET_GLOBAL_INT_DATA::NAME => {
33550 Some(SET_POSITION_TARGET_GLOBAL_INT_DATA::ID)
33551 }
33552 SMART_BATTERY_INFO_DATA::NAME => Some(SMART_BATTERY_INFO_DATA::ID),
33553 SET_GPS_GLOBAL_ORIGIN_DATA::NAME => Some(SET_GPS_GLOBAL_ORIGIN_DATA::ID),
33554 VIBRATION_DATA::NAME => Some(VIBRATION_DATA::ID),
33555 GIMBAL_MANAGER_STATUS_DATA::NAME => Some(GIMBAL_MANAGER_STATUS_DATA::ID),
33556 MISSION_ITEM_INT_DATA::NAME => Some(MISSION_ITEM_INT_DATA::ID),
33557 POWER_STATUS_DATA::NAME => Some(POWER_STATUS_DATA::ID),
33558 LOGGING_DATA_DATA::NAME => Some(LOGGING_DATA_DATA::ID),
33559 CHANGE_OPERATOR_CONTROL_ACK_DATA::NAME => Some(CHANGE_OPERATOR_CONTROL_ACK_DATA::ID),
33560 GPS_RTK_DATA::NAME => Some(GPS_RTK_DATA::ID),
33561 FLIGHT_INFORMATION_DATA::NAME => Some(FLIGHT_INFORMATION_DATA::ID),
33562 SUPPORTED_TUNES_DATA::NAME => Some(SUPPORTED_TUNES_DATA::ID),
33563 WIFI_CONFIG_AP_DATA::NAME => Some(WIFI_CONFIG_AP_DATA::ID),
33564 TERRAIN_CHECK_DATA::NAME => Some(TERRAIN_CHECK_DATA::ID),
33565 RAW_PRESSURE_DATA::NAME => Some(RAW_PRESSURE_DATA::ID),
33566 OPEN_DRONE_ID_AUTHENTICATION_DATA::NAME => Some(OPEN_DRONE_ID_AUTHENTICATION_DATA::ID),
33567 ESC_INFO_DATA::NAME => Some(ESC_INFO_DATA::ID),
33568 DISTANCE_SENSOR_DATA::NAME => Some(DISTANCE_SENSOR_DATA::ID),
33569 HIL_RC_INPUTS_RAW_DATA::NAME => Some(HIL_RC_INPUTS_RAW_DATA::ID),
33570 ISBD_LINK_STATUS_DATA::NAME => Some(ISBD_LINK_STATUS_DATA::ID),
33571 RC_CHANNELS_SCALED_DATA::NAME => Some(RC_CHANNELS_SCALED_DATA::ID),
33572 SCALED_IMU2_DATA::NAME => Some(SCALED_IMU2_DATA::ID),
33573 HIL_SENSOR_DATA::NAME => Some(HIL_SENSOR_DATA::ID),
33574 RESOURCE_REQUEST_DATA::NAME => Some(RESOURCE_REQUEST_DATA::ID),
33575 CAMERA_THERMAL_RANGE_DATA::NAME => Some(CAMERA_THERMAL_RANGE_DATA::ID),
33576 TIMESYNC_DATA::NAME => Some(TIMESYNC_DATA::ID),
33577 OPEN_DRONE_ID_MESSAGE_PACK_DATA::NAME => Some(OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID),
33578 LOG_REQUEST_DATA_DATA::NAME => Some(LOG_REQUEST_DATA_DATA::ID),
33579 COMPONENT_METADATA_DATA::NAME => Some(COMPONENT_METADATA_DATA::ID),
33580 MAG_CAL_REPORT_DATA::NAME => Some(MAG_CAL_REPORT_DATA::ID),
33581 NAMED_VALUE_INT_DATA::NAME => Some(NAMED_VALUE_INT_DATA::ID),
33582 SAFETY_ALLOWED_AREA_DATA::NAME => Some(SAFETY_ALLOWED_AREA_DATA::ID),
33583 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::NAME => {
33584 Some(GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID)
33585 }
33586 ESC_STATUS_DATA::NAME => Some(ESC_STATUS_DATA::ID),
33587 PARAM_EXT_REQUEST_READ_DATA::NAME => Some(PARAM_EXT_REQUEST_READ_DATA::ID),
33588 SCALED_IMU3_DATA::NAME => Some(SCALED_IMU3_DATA::ID),
33589 ESTIMATOR_STATUS_DATA::NAME => Some(ESTIMATOR_STATUS_DATA::ID),
33590 PARAM_EXT_ACK_DATA::NAME => Some(PARAM_EXT_ACK_DATA::ID),
33591 V2_EXTENSION_DATA::NAME => Some(V2_EXTENSION_DATA::ID),
33592 SET_ACTUATOR_CONTROL_TARGET_DATA::NAME => Some(SET_ACTUATOR_CONTROL_TARGET_DATA::ID),
33593 RC_CHANNELS_OVERRIDE_DATA::NAME => Some(RC_CHANNELS_OVERRIDE_DATA::ID),
33594 DATA_TRANSMISSION_HANDSHAKE_DATA::NAME => Some(DATA_TRANSMISSION_HANDSHAKE_DATA::ID),
33595 LOCAL_POSITION_NED_DATA::NAME => Some(LOCAL_POSITION_NED_DATA::ID),
33596 EXTENDED_SYS_STATE_DATA::NAME => Some(EXTENDED_SYS_STATE_DATA::ID),
33597 FENCE_STATUS_DATA::NAME => Some(FENCE_STATUS_DATA::ID),
33598 ONBOARD_COMPUTER_STATUS_DATA::NAME => Some(ONBOARD_COMPUTER_STATUS_DATA::ID),
33599 MISSION_REQUEST_LIST_DATA::NAME => Some(MISSION_REQUEST_LIST_DATA::ID),
33600 MESSAGE_INTERVAL_DATA::NAME => Some(MESSAGE_INTERVAL_DATA::ID),
33601 TERRAIN_REQUEST_DATA::NAME => Some(TERRAIN_REQUEST_DATA::ID),
33602 SCALED_PRESSURE3_DATA::NAME => Some(SCALED_PRESSURE3_DATA::ID),
33603 REQUEST_EVENT_DATA::NAME => Some(REQUEST_EVENT_DATA::ID),
33604 SET_ATTITUDE_TARGET_DATA::NAME => Some(SET_ATTITUDE_TARGET_DATA::ID),
33605 SET_POSITION_TARGET_LOCAL_NED_DATA::NAME => {
33606 Some(SET_POSITION_TARGET_LOCAL_NED_DATA::ID)
33607 }
33608 LOGGING_ACK_DATA::NAME => Some(LOGGING_ACK_DATA::ID),
33609 LOG_ERASE_DATA::NAME => Some(LOG_ERASE_DATA::ID),
33610 OPEN_DRONE_ID_LOCATION_DATA::NAME => Some(OPEN_DRONE_ID_LOCATION_DATA::ID),
33611 UAVIONIX_ADSB_OUT_CFG_DATA::NAME => Some(UAVIONIX_ADSB_OUT_CFG_DATA::ID),
33612 TRAJECTORY_REPRESENTATION_BEZIER_DATA::NAME => {
33613 Some(TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID)
33614 }
33615 SIM_STATE_DATA::NAME => Some(SIM_STATE_DATA::ID),
33616 ODOMETRY_DATA::NAME => Some(ODOMETRY_DATA::ID),
33617 VISION_POSITION_ESTIMATE_DATA::NAME => Some(VISION_POSITION_ESTIMATE_DATA::ID),
33618 PARAM_REQUEST_READ_DATA::NAME => Some(PARAM_REQUEST_READ_DATA::ID),
33619 BATTERY_INFO_DATA::NAME => Some(BATTERY_INFO_DATA::ID),
33620 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::NAME => {
33621 Some(LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID)
33622 }
33623 VIDEO_STREAM_STATUS_DATA::NAME => Some(VIDEO_STREAM_STATUS_DATA::ID),
33624 ATT_POS_MOCAP_DATA::NAME => Some(ATT_POS_MOCAP_DATA::ID),
33625 UAVIONIX_ADSB_GET_DATA::NAME => Some(UAVIONIX_ADSB_GET_DATA::ID),
33626 MISSION_ITEM_DATA::NAME => Some(MISSION_ITEM_DATA::ID),
33627 VISION_SPEED_ESTIMATE_DATA::NAME => Some(VISION_SPEED_ESTIMATE_DATA::ID),
33628 MISSION_WRITE_PARTIAL_LIST_DATA::NAME => Some(MISSION_WRITE_PARTIAL_LIST_DATA::ID),
33629 VFR_HUD_DATA::NAME => Some(VFR_HUD_DATA::ID),
33630 POSITION_TARGET_LOCAL_NED_DATA::NAME => Some(POSITION_TARGET_LOCAL_NED_DATA::ID),
33631 MISSION_CLEAR_ALL_DATA::NAME => Some(MISSION_CLEAR_ALL_DATA::ID),
33632 MANUAL_CONTROL_DATA::NAME => Some(MANUAL_CONTROL_DATA::ID),
33633 AVAILABLE_MODES_DATA::NAME => Some(AVAILABLE_MODES_DATA::ID),
33634 TIME_ESTIMATE_TO_TARGET_DATA::NAME => Some(TIME_ESTIMATE_TO_TARGET_DATA::ID),
33635 GPS_RAW_INT_DATA::NAME => Some(GPS_RAW_INT_DATA::ID),
33636 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::NAME => {
33637 Some(UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID)
33638 }
33639 VICON_POSITION_ESTIMATE_DATA::NAME => Some(VICON_POSITION_ESTIMATE_DATA::ID),
33640 SCALED_PRESSURE2_DATA::NAME => Some(SCALED_PRESSURE2_DATA::ID),
33641 CONTROL_SYSTEM_STATE_DATA::NAME => Some(CONTROL_SYSTEM_STATE_DATA::ID),
33642 MISSION_REQUEST_PARTIAL_LIST_DATA::NAME => Some(MISSION_REQUEST_PARTIAL_LIST_DATA::ID),
33643 HOME_POSITION_DATA::NAME => Some(HOME_POSITION_DATA::ID),
33644 CAMERA_TRACKING_IMAGE_STATUS_DATA::NAME => Some(CAMERA_TRACKING_IMAGE_STATUS_DATA::ID),
33645 ACTUATOR_OUTPUT_STATUS_DATA::NAME => Some(ACTUATOR_OUTPUT_STATUS_DATA::ID),
33646 LOG_REQUEST_END_DATA::NAME => Some(LOG_REQUEST_END_DATA::ID),
33647 RC_CHANNELS_DATA::NAME => Some(RC_CHANNELS_DATA::ID),
33648 ATTITUDE_QUATERNION_COV_DATA::NAME => Some(ATTITUDE_QUATERNION_COV_DATA::ID),
33649 CAMERA_TRIGGER_DATA::NAME => Some(CAMERA_TRIGGER_DATA::ID),
33650 FOLLOW_TARGET_DATA::NAME => Some(FOLLOW_TARGET_DATA::ID),
33651 GLOBAL_POSITION_INT_COV_DATA::NAME => Some(GLOBAL_POSITION_INT_COV_DATA::ID),
33652 MOUNT_ORIENTATION_DATA::NAME => Some(MOUNT_ORIENTATION_DATA::ID),
33653 GENERATOR_STATUS_DATA::NAME => Some(GENERATOR_STATUS_DATA::ID),
33654 GPS_RTCM_DATA_DATA::NAME => Some(GPS_RTCM_DATA_DATA::ID),
33655 NAV_CONTROLLER_OUTPUT_DATA::NAME => Some(NAV_CONTROLLER_OUTPUT_DATA::ID),
33656 GLOBAL_VISION_POSITION_ESTIMATE_DATA::NAME => {
33657 Some(GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID)
33658 }
33659 PARAM_EXT_VALUE_DATA::NAME => Some(PARAM_EXT_VALUE_DATA::ID),
33660 CAMERA_CAPTURE_STATUS_DATA::NAME => Some(CAMERA_CAPTURE_STATUS_DATA::ID),
33661 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::NAME => {
33662 Some(GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID)
33663 }
33664 GIMBAL_MANAGER_INFORMATION_DATA::NAME => Some(GIMBAL_MANAGER_INFORMATION_DATA::ID),
33665 HIGH_LATENCY2_DATA::NAME => Some(HIGH_LATENCY2_DATA::ID),
33666 HIGHRES_IMU_DATA::NAME => Some(HIGHRES_IMU_DATA::ID),
33667 HIL_CONTROLS_DATA::NAME => Some(HIL_CONTROLS_DATA::ID),
33668 MISSION_REQUEST_DATA::NAME => Some(MISSION_REQUEST_DATA::ID),
33669 LANDING_TARGET_DATA::NAME => Some(LANDING_TARGET_DATA::ID),
33670 LOG_REQUEST_LIST_DATA::NAME => Some(LOG_REQUEST_LIST_DATA::ID),
33671 CAMERA_FOV_STATUS_DATA::NAME => Some(CAMERA_FOV_STATUS_DATA::ID),
33672 LOG_ENTRY_DATA::NAME => Some(LOG_ENTRY_DATA::ID),
33673 GPS_INJECT_DATA_DATA::NAME => Some(GPS_INJECT_DATA_DATA::ID),
33674 PARAM_VALUE_DATA::NAME => Some(PARAM_VALUE_DATA::ID),
33675 GIMBAL_MANAGER_SET_PITCHYAW_DATA::NAME => Some(GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID),
33676 CURRENT_EVENT_SEQUENCE_DATA::NAME => Some(CURRENT_EVENT_SEQUENCE_DATA::ID),
33677 CAMERA_INFORMATION_DATA::NAME => Some(CAMERA_INFORMATION_DATA::ID),
33678 OPEN_DRONE_ID_OPERATOR_ID_DATA::NAME => Some(OPEN_DRONE_ID_OPERATOR_ID_DATA::ID),
33679 COMPONENT_INFORMATION_DATA::NAME => Some(COMPONENT_INFORMATION_DATA::ID),
33680 COMMAND_LONG_DATA::NAME => Some(COMMAND_LONG_DATA::ID),
33681 PARAM_EXT_SET_DATA::NAME => Some(PARAM_EXT_SET_DATA::ID),
33682 GPS_INPUT_DATA::NAME => Some(GPS_INPUT_DATA::ID),
33683 SET_MODE_DATA::NAME => Some(SET_MODE_DATA::ID),
33684 AIS_VESSEL_DATA::NAME => Some(AIS_VESSEL_DATA::ID),
33685 ATTITUDE_QUATERNION_DATA::NAME => Some(ATTITUDE_QUATERNION_DATA::ID),
33686 CURRENT_MODE_DATA::NAME => Some(CURRENT_MODE_DATA::ID),
33687 GIMBAL_DEVICE_SET_ATTITUDE_DATA::NAME => Some(GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID),
33688 HYGROMETER_SENSOR_DATA::NAME => Some(HYGROMETER_SENSOR_DATA::ID),
33689 PARAM_MAP_RC_DATA::NAME => Some(PARAM_MAP_RC_DATA::ID),
33690 COMPONENT_INFORMATION_BASIC_DATA::NAME => Some(COMPONENT_INFORMATION_BASIC_DATA::ID),
33691 OPEN_DRONE_ID_SYSTEM_DATA::NAME => Some(OPEN_DRONE_ID_SYSTEM_DATA::ID),
33692 COMMAND_ACK_DATA::NAME => Some(COMMAND_ACK_DATA::ID),
33693 SERIAL_CONTROL_DATA::NAME => Some(SERIAL_CONTROL_DATA::ID),
33694 _ => None,
33695 }
33696 }
33697 fn default_message_from_id(id: u32) -> Option<Self> {
33698 match id {
33699 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::default())),
33700 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::default())),
33701 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::default())),
33702 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::default())),
33703 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::default())),
33704 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
33705 OPEN_DRONE_ID_ARM_STATUS_DATA::default(),
33706 )),
33707 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::default())),
33708 MISSION_CURRENT_DATA::ID => {
33709 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::default()))
33710 }
33711 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::default())),
33712 OBSTACLE_DISTANCE_DATA::ID => {
33713 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::default()))
33714 }
33715 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
33716 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
33717 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::default(),
33718 ))
33719 }
33720 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
33721 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
33722 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::default(),
33723 ))
33724 }
33725 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
33726 CAMERA_IMAGE_CAPTURED_DATA::default(),
33727 )),
33728 PROTOCOL_VERSION_DATA::ID => {
33729 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::default()))
33730 }
33731 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::default())),
33732 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
33733 UTM_GLOBAL_POSITION_DATA::default(),
33734 )),
33735 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::default())),
33736 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::default())),
33737 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
33738 OPEN_DRONE_ID_BASIC_ID_DATA::default(),
33739 )),
33740 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::default())),
33741 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::default())),
33742 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::default())),
33743 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(
33744 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::default(),
33745 )),
33746 PING_DATA::ID => Some(Self::PING(PING_DATA::default())),
33747 HIL_OPTICAL_FLOW_DATA::ID => {
33748 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::default()))
33749 }
33750 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
33751 VIDEO_STREAM_INFORMATION_DATA::default(),
33752 )),
33753 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
33754 LOCAL_POSITION_NED_COV_DATA::default(),
33755 )),
33756 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::default())),
33757 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
33758 HIL_ACTUATOR_CONTROLS_DATA::default(),
33759 )),
33760 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::default())),
33761 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
33762 Some(Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(
33763 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::default(),
33764 ))
33765 }
33766 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
33767 HIL_STATE_QUATERNION_DATA::default(),
33768 )),
33769 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_STATUS(
33770 UAVIONIX_ADSB_OUT_STATUS_DATA::default(),
33771 )),
33772 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::default())),
33773 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::default())),
33774 OPTICAL_FLOW_RAD_DATA::ID => {
33775 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::default()))
33776 }
33777 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
33778 CAMERA_TRACKING_GEO_STATUS_DATA::default(),
33779 )),
33780 CELLULAR_CONFIG_DATA::ID => {
33781 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::default()))
33782 }
33783 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::default())),
33784 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::default())),
33785 UAVCAN_NODE_STATUS_DATA::ID => {
33786 Some(Self::UAVCAN_NODE_STATUS(UAVCAN_NODE_STATUS_DATA::default()))
33787 }
33788 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
33789 STORAGE_INFORMATION_DATA::default(),
33790 )),
33791 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
33792 MISSION_REQUEST_INT_DATA::default(),
33793 )),
33794 SCALED_PRESSURE_DATA::ID => {
33795 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::default()))
33796 }
33797 ENCAPSULATED_DATA_DATA::ID => {
33798 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::default()))
33799 }
33800 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::default())),
33801 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::default())),
33802 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
33803 AVAILABLE_MODES_MONITOR_DATA::default(),
33804 )),
33805 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::default())),
33806 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::default())),
33807 MANUAL_SETPOINT_DATA::ID => {
33808 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::default()))
33809 }
33810 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
33811 MISSION_SET_CURRENT_DATA::default(),
33812 )),
33813 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::default())),
33814 CAN_FILTER_MODIFY_DATA::ID => {
33815 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::default()))
33816 }
33817 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::default())),
33818 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::default())),
33819 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::default())),
33820 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
33821 OPEN_DRONE_ID_SELF_ID_DATA::default(),
33822 )),
33823 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::default())),
33824 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CONTROL(
33825 UAVIONIX_ADSB_OUT_CONTROL_DATA::default(),
33826 )),
33827 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
33828 RESPONSE_EVENT_ERROR_DATA::default(),
33829 )),
33830 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::default())),
33831 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::default())),
33832 DEBUG_FLOAT_ARRAY_DATA::ID => {
33833 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::default()))
33834 }
33835 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::default())),
33836 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
33837 FILE_TRANSFER_PROTOCOL_DATA::default(),
33838 )),
33839 CELLULAR_STATUS_DATA::ID => {
33840 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::default()))
33841 }
33842 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
33843 REQUEST_DATA_STREAM_DATA::default(),
33844 )),
33845 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
33846 PARAM_EXT_REQUEST_LIST_DATA::default(),
33847 )),
33848 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::default())),
33849 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::default())),
33850 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::default())),
33851 NAMED_VALUE_FLOAT_DATA::ID => {
33852 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::default()))
33853 }
33854 GPS_GLOBAL_ORIGIN_DATA::ID => {
33855 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::default()))
33856 }
33857 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
33858 POSITION_TARGET_GLOBAL_INT_DATA::default(),
33859 )),
33860 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::default())),
33861 PARAM_REQUEST_LIST_DATA::ID => {
33862 Some(Self::PARAM_REQUEST_LIST(PARAM_REQUEST_LIST_DATA::default()))
33863 }
33864 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
33865 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::default(),
33866 )),
33867 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::default())),
33868 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::default())),
33869 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_DYNAMIC(
33870 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::default(),
33871 )),
33872 CAMERA_SETTINGS_DATA::ID => {
33873 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::default()))
33874 }
33875 SERVO_OUTPUT_RAW_DATA::ID => {
33876 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::default()))
33877 }
33878 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
33879 ACTUATOR_CONTROL_TARGET_DATA::default(),
33880 )),
33881 ATTITUDE_TARGET_DATA::ID => {
33882 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::default()))
33883 }
33884 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::default())),
33885 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::default())),
33886 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::default())),
33887 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
33888 CHANGE_OPERATOR_CONTROL_DATA::default(),
33889 )),
33890 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::default())),
33891 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::default())),
33892 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::default())),
33893 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::default())),
33894 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
33895 ORBIT_EXECUTION_STATUS_DATA::default(),
33896 )),
33897 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
33898 GLOBAL_POSITION_INT_DATA::default(),
33899 )),
33900 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::default())),
33901 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
33902 SAFETY_SET_ALLOWED_AREA_DATA::default(),
33903 )),
33904 SET_HOME_POSITION_DATA::ID => {
33905 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::default()))
33906 }
33907 AUTOPILOT_VERSION_DATA::ID => {
33908 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::default()))
33909 }
33910 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::default())),
33911 ILLUMINATOR_STATUS_DATA::ID => {
33912 Some(Self::ILLUMINATOR_STATUS(ILLUMINATOR_STATUS_DATA::default()))
33913 }
33914 UAVCAN_NODE_INFO_DATA::ID => {
33915 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::default()))
33916 }
33917 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
33918 GIMBAL_DEVICE_INFORMATION_DATA::default(),
33919 )),
33920 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
33921 GIMBAL_MANAGER_SET_ATTITUDE_DATA::default(),
33922 )),
33923 LOGGING_DATA_ACKED_DATA::ID => {
33924 Some(Self::LOGGING_DATA_ACKED(LOGGING_DATA_ACKED_DATA::default()))
33925 }
33926 RC_CHANNELS_RAW_DATA::ID => {
33927 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::default()))
33928 }
33929 LINK_NODE_STATUS_DATA::ID => {
33930 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::default()))
33931 }
33932 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
33933 MISSION_ITEM_REACHED_DATA::default(),
33934 )),
33935 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
33936 SET_POSITION_TARGET_GLOBAL_INT_DATA::default(),
33937 )),
33938 SMART_BATTERY_INFO_DATA::ID => {
33939 Some(Self::SMART_BATTERY_INFO(SMART_BATTERY_INFO_DATA::default()))
33940 }
33941 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
33942 SET_GPS_GLOBAL_ORIGIN_DATA::default(),
33943 )),
33944 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::default())),
33945 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
33946 GIMBAL_MANAGER_STATUS_DATA::default(),
33947 )),
33948 MISSION_ITEM_INT_DATA::ID => {
33949 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::default()))
33950 }
33951 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::default())),
33952 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::default())),
33953 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
33954 CHANGE_OPERATOR_CONTROL_ACK_DATA::default(),
33955 )),
33956 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::default())),
33957 FLIGHT_INFORMATION_DATA::ID => {
33958 Some(Self::FLIGHT_INFORMATION(FLIGHT_INFORMATION_DATA::default()))
33959 }
33960 SUPPORTED_TUNES_DATA::ID => {
33961 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::default()))
33962 }
33963 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::default())),
33964 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::default())),
33965 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::default())),
33966 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
33967 OPEN_DRONE_ID_AUTHENTICATION_DATA::default(),
33968 )),
33969 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::default())),
33970 DISTANCE_SENSOR_DATA::ID => {
33971 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::default()))
33972 }
33973 HIL_RC_INPUTS_RAW_DATA::ID => {
33974 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::default()))
33975 }
33976 ISBD_LINK_STATUS_DATA::ID => {
33977 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::default()))
33978 }
33979 RC_CHANNELS_SCALED_DATA::ID => {
33980 Some(Self::RC_CHANNELS_SCALED(RC_CHANNELS_SCALED_DATA::default()))
33981 }
33982 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::default())),
33983 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::default())),
33984 RESOURCE_REQUEST_DATA::ID => {
33985 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::default()))
33986 }
33987 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
33988 CAMERA_THERMAL_RANGE_DATA::default(),
33989 )),
33990 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::default())),
33991 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
33992 OPEN_DRONE_ID_MESSAGE_PACK_DATA::default(),
33993 )),
33994 LOG_REQUEST_DATA_DATA::ID => {
33995 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::default()))
33996 }
33997 COMPONENT_METADATA_DATA::ID => {
33998 Some(Self::COMPONENT_METADATA(COMPONENT_METADATA_DATA::default()))
33999 }
34000 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::default())),
34001 NAMED_VALUE_INT_DATA::ID => {
34002 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::default()))
34003 }
34004 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
34005 SAFETY_ALLOWED_AREA_DATA::default(),
34006 )),
34007 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
34008 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::default(),
34009 )),
34010 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::default())),
34011 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
34012 PARAM_EXT_REQUEST_READ_DATA::default(),
34013 )),
34014 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::default())),
34015 ESTIMATOR_STATUS_DATA::ID => {
34016 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::default()))
34017 }
34018 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::default())),
34019 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::default())),
34020 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
34021 SET_ACTUATOR_CONTROL_TARGET_DATA::default(),
34022 )),
34023 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
34024 RC_CHANNELS_OVERRIDE_DATA::default(),
34025 )),
34026 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
34027 DATA_TRANSMISSION_HANDSHAKE_DATA::default(),
34028 )),
34029 LOCAL_POSITION_NED_DATA::ID => {
34030 Some(Self::LOCAL_POSITION_NED(LOCAL_POSITION_NED_DATA::default()))
34031 }
34032 EXTENDED_SYS_STATE_DATA::ID => {
34033 Some(Self::EXTENDED_SYS_STATE(EXTENDED_SYS_STATE_DATA::default()))
34034 }
34035 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::default())),
34036 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
34037 ONBOARD_COMPUTER_STATUS_DATA::default(),
34038 )),
34039 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
34040 MISSION_REQUEST_LIST_DATA::default(),
34041 )),
34042 MESSAGE_INTERVAL_DATA::ID => {
34043 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::default()))
34044 }
34045 TERRAIN_REQUEST_DATA::ID => {
34046 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::default()))
34047 }
34048 SCALED_PRESSURE3_DATA::ID => {
34049 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::default()))
34050 }
34051 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::default())),
34052 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
34053 SET_ATTITUDE_TARGET_DATA::default(),
34054 )),
34055 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
34056 SET_POSITION_TARGET_LOCAL_NED_DATA::default(),
34057 )),
34058 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::default())),
34059 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::default())),
34060 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
34061 OPEN_DRONE_ID_LOCATION_DATA::default(),
34062 )),
34063 UAVIONIX_ADSB_OUT_CFG_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG(
34064 UAVIONIX_ADSB_OUT_CFG_DATA::default(),
34065 )),
34066 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
34067 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
34068 TRAJECTORY_REPRESENTATION_BEZIER_DATA::default(),
34069 ))
34070 }
34071 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::default())),
34072 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::default())),
34073 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
34074 VISION_POSITION_ESTIMATE_DATA::default(),
34075 )),
34076 PARAM_REQUEST_READ_DATA::ID => {
34077 Some(Self::PARAM_REQUEST_READ(PARAM_REQUEST_READ_DATA::default()))
34078 }
34079 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::default())),
34080 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
34081 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
34082 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::default(),
34083 ))
34084 }
34085 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
34086 VIDEO_STREAM_STATUS_DATA::default(),
34087 )),
34088 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::default())),
34089 UAVIONIX_ADSB_GET_DATA::ID => {
34090 Some(Self::UAVIONIX_ADSB_GET(UAVIONIX_ADSB_GET_DATA::default()))
34091 }
34092 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::default())),
34093 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
34094 VISION_SPEED_ESTIMATE_DATA::default(),
34095 )),
34096 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
34097 MISSION_WRITE_PARTIAL_LIST_DATA::default(),
34098 )),
34099 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::default())),
34100 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
34101 POSITION_TARGET_LOCAL_NED_DATA::default(),
34102 )),
34103 MISSION_CLEAR_ALL_DATA::ID => {
34104 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::default()))
34105 }
34106 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::default())),
34107 AVAILABLE_MODES_DATA::ID => {
34108 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::default()))
34109 }
34110 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
34111 TIME_ESTIMATE_TO_TARGET_DATA::default(),
34112 )),
34113 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::default())),
34114 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
34115 Some(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(
34116 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::default(),
34117 ))
34118 }
34119 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
34120 VICON_POSITION_ESTIMATE_DATA::default(),
34121 )),
34122 SCALED_PRESSURE2_DATA::ID => {
34123 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::default()))
34124 }
34125 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
34126 CONTROL_SYSTEM_STATE_DATA::default(),
34127 )),
34128 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
34129 MISSION_REQUEST_PARTIAL_LIST_DATA::default(),
34130 )),
34131 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::default())),
34132 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
34133 CAMERA_TRACKING_IMAGE_STATUS_DATA::default(),
34134 )),
34135 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
34136 ACTUATOR_OUTPUT_STATUS_DATA::default(),
34137 )),
34138 LOG_REQUEST_END_DATA::ID => {
34139 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::default()))
34140 }
34141 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::default())),
34142 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
34143 ATTITUDE_QUATERNION_COV_DATA::default(),
34144 )),
34145 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::default())),
34146 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::default())),
34147 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
34148 GLOBAL_POSITION_INT_COV_DATA::default(),
34149 )),
34150 MOUNT_ORIENTATION_DATA::ID => {
34151 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::default()))
34152 }
34153 GENERATOR_STATUS_DATA::ID => {
34154 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::default()))
34155 }
34156 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::default())),
34157 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
34158 NAV_CONTROLLER_OUTPUT_DATA::default(),
34159 )),
34160 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
34161 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
34162 GLOBAL_VISION_POSITION_ESTIMATE_DATA::default(),
34163 ))
34164 }
34165 PARAM_EXT_VALUE_DATA::ID => {
34166 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::default()))
34167 }
34168 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
34169 CAMERA_CAPTURE_STATUS_DATA::default(),
34170 )),
34171 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
34172 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
34173 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::default(),
34174 ))
34175 }
34176 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
34177 GIMBAL_MANAGER_INFORMATION_DATA::default(),
34178 )),
34179 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::default())),
34180 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::default())),
34181 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::default())),
34182 MISSION_REQUEST_DATA::ID => {
34183 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::default()))
34184 }
34185 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::default())),
34186 LOG_REQUEST_LIST_DATA::ID => {
34187 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::default()))
34188 }
34189 CAMERA_FOV_STATUS_DATA::ID => {
34190 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::default()))
34191 }
34192 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::default())),
34193 GPS_INJECT_DATA_DATA::ID => {
34194 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::default()))
34195 }
34196 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::default())),
34197 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
34198 GIMBAL_MANAGER_SET_PITCHYAW_DATA::default(),
34199 )),
34200 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
34201 CURRENT_EVENT_SEQUENCE_DATA::default(),
34202 )),
34203 CAMERA_INFORMATION_DATA::ID => {
34204 Some(Self::CAMERA_INFORMATION(CAMERA_INFORMATION_DATA::default()))
34205 }
34206 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
34207 OPEN_DRONE_ID_OPERATOR_ID_DATA::default(),
34208 )),
34209 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
34210 COMPONENT_INFORMATION_DATA::default(),
34211 )),
34212 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::default())),
34213 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::default())),
34214 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::default())),
34215 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::default())),
34216 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::default())),
34217 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
34218 ATTITUDE_QUATERNION_DATA::default(),
34219 )),
34220 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::default())),
34221 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
34222 GIMBAL_DEVICE_SET_ATTITUDE_DATA::default(),
34223 )),
34224 HYGROMETER_SENSOR_DATA::ID => {
34225 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::default()))
34226 }
34227 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::default())),
34228 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
34229 COMPONENT_INFORMATION_BASIC_DATA::default(),
34230 )),
34231 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
34232 OPEN_DRONE_ID_SYSTEM_DATA::default(),
34233 )),
34234 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::default())),
34235 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::default())),
34236 _ => None,
34237 }
34238 }
34239 #[cfg(feature = "arbitrary")]
34240 fn random_message_from_id<R: rand::RngCore>(id: u32, rng: &mut R) -> Option<Self> {
34241 match id {
34242 MISSION_COUNT_DATA::ID => Some(Self::MISSION_COUNT(MISSION_COUNT_DATA::random(rng))),
34243 SYSTEM_TIME_DATA::ID => Some(Self::SYSTEM_TIME(SYSTEM_TIME_DATA::random(rng))),
34244 SYS_STATUS_DATA::ID => Some(Self::SYS_STATUS(SYS_STATUS_DATA::random(rng))),
34245 ADSB_VEHICLE_DATA::ID => Some(Self::ADSB_VEHICLE(ADSB_VEHICLE_DATA::random(rng))),
34246 TUNNEL_DATA::ID => Some(Self::TUNNEL(TUNNEL_DATA::random(rng))),
34247 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => Some(Self::OPEN_DRONE_ID_ARM_STATUS(
34248 OPEN_DRONE_ID_ARM_STATUS_DATA::random(rng),
34249 )),
34250 RAW_IMU_DATA::ID => Some(Self::RAW_IMU(RAW_IMU_DATA::random(rng))),
34251 MISSION_CURRENT_DATA::ID => {
34252 Some(Self::MISSION_CURRENT(MISSION_CURRENT_DATA::random(rng)))
34253 }
34254 HIL_STATE_DATA::ID => Some(Self::HIL_STATE(HIL_STATE_DATA::random(rng))),
34255 OBSTACLE_DISTANCE_DATA::ID => {
34256 Some(Self::OBSTACLE_DISTANCE(OBSTACLE_DISTANCE_DATA::random(rng)))
34257 }
34258 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
34259 Some(Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(
34260 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::random(rng),
34261 ))
34262 }
34263 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
34264 Some(Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(
34265 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::random(rng),
34266 ))
34267 }
34268 CAMERA_IMAGE_CAPTURED_DATA::ID => Some(Self::CAMERA_IMAGE_CAPTURED(
34269 CAMERA_IMAGE_CAPTURED_DATA::random(rng),
34270 )),
34271 PROTOCOL_VERSION_DATA::ID => {
34272 Some(Self::PROTOCOL_VERSION(PROTOCOL_VERSION_DATA::random(rng)))
34273 }
34274 GPS2_RAW_DATA::ID => Some(Self::GPS2_RAW(GPS2_RAW_DATA::random(rng))),
34275 UTM_GLOBAL_POSITION_DATA::ID => Some(Self::UTM_GLOBAL_POSITION(
34276 UTM_GLOBAL_POSITION_DATA::random(rng),
34277 )),
34278 HIL_GPS_DATA::ID => Some(Self::HIL_GPS(HIL_GPS_DATA::random(rng))),
34279 HIGH_LATENCY_DATA::ID => Some(Self::HIGH_LATENCY(HIGH_LATENCY_DATA::random(rng))),
34280 OPEN_DRONE_ID_BASIC_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_BASIC_ID(
34281 OPEN_DRONE_ID_BASIC_ID_DATA::random(rng),
34282 )),
34283 BATTERY_STATUS_DATA::ID => Some(Self::BATTERY_STATUS(BATTERY_STATUS_DATA::random(rng))),
34284 EFI_STATUS_DATA::ID => Some(Self::EFI_STATUS(EFI_STATUS_DATA::random(rng))),
34285 WINCH_STATUS_DATA::ID => Some(Self::WINCH_STATUS(WINCH_STATUS_DATA::random(rng))),
34286 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(
34287 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::random(rng),
34288 )),
34289 PING_DATA::ID => Some(Self::PING(PING_DATA::random(rng))),
34290 HIL_OPTICAL_FLOW_DATA::ID => {
34291 Some(Self::HIL_OPTICAL_FLOW(HIL_OPTICAL_FLOW_DATA::random(rng)))
34292 }
34293 VIDEO_STREAM_INFORMATION_DATA::ID => Some(Self::VIDEO_STREAM_INFORMATION(
34294 VIDEO_STREAM_INFORMATION_DATA::random(rng),
34295 )),
34296 LOCAL_POSITION_NED_COV_DATA::ID => Some(Self::LOCAL_POSITION_NED_COV(
34297 LOCAL_POSITION_NED_COV_DATA::random(rng),
34298 )),
34299 AUTH_KEY_DATA::ID => Some(Self::AUTH_KEY(AUTH_KEY_DATA::random(rng))),
34300 HIL_ACTUATOR_CONTROLS_DATA::ID => Some(Self::HIL_ACTUATOR_CONTROLS(
34301 HIL_ACTUATOR_CONTROLS_DATA::random(rng),
34302 )),
34303 COLLISION_DATA::ID => Some(Self::COLLISION(COLLISION_DATA::random(rng))),
34304 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
34305 Some(Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(
34306 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::random(rng),
34307 ))
34308 }
34309 HIL_STATE_QUATERNION_DATA::ID => Some(Self::HIL_STATE_QUATERNION(
34310 HIL_STATE_QUATERNION_DATA::random(rng),
34311 )),
34312 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_STATUS(
34313 UAVIONIX_ADSB_OUT_STATUS_DATA::random(rng),
34314 )),
34315 MISSION_ACK_DATA::ID => Some(Self::MISSION_ACK(MISSION_ACK_DATA::random(rng))),
34316 WHEEL_DISTANCE_DATA::ID => Some(Self::WHEEL_DISTANCE(WHEEL_DISTANCE_DATA::random(rng))),
34317 OPTICAL_FLOW_RAD_DATA::ID => {
34318 Some(Self::OPTICAL_FLOW_RAD(OPTICAL_FLOW_RAD_DATA::random(rng)))
34319 }
34320 CAMERA_TRACKING_GEO_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_GEO_STATUS(
34321 CAMERA_TRACKING_GEO_STATUS_DATA::random(rng),
34322 )),
34323 CELLULAR_CONFIG_DATA::ID => {
34324 Some(Self::CELLULAR_CONFIG(CELLULAR_CONFIG_DATA::random(rng)))
34325 }
34326 DATA_STREAM_DATA::ID => Some(Self::DATA_STREAM(DATA_STREAM_DATA::random(rng))),
34327 PARAM_SET_DATA::ID => Some(Self::PARAM_SET(PARAM_SET_DATA::random(rng))),
34328 UAVCAN_NODE_STATUS_DATA::ID => Some(Self::UAVCAN_NODE_STATUS(
34329 UAVCAN_NODE_STATUS_DATA::random(rng),
34330 )),
34331 STORAGE_INFORMATION_DATA::ID => Some(Self::STORAGE_INFORMATION(
34332 STORAGE_INFORMATION_DATA::random(rng),
34333 )),
34334 MISSION_REQUEST_INT_DATA::ID => Some(Self::MISSION_REQUEST_INT(
34335 MISSION_REQUEST_INT_DATA::random(rng),
34336 )),
34337 SCALED_PRESSURE_DATA::ID => {
34338 Some(Self::SCALED_PRESSURE(SCALED_PRESSURE_DATA::random(rng)))
34339 }
34340 ENCAPSULATED_DATA_DATA::ID => {
34341 Some(Self::ENCAPSULATED_DATA(ENCAPSULATED_DATA_DATA::random(rng)))
34342 }
34343 PLAY_TUNE_DATA::ID => Some(Self::PLAY_TUNE(PLAY_TUNE_DATA::random(rng))),
34344 CANFD_FRAME_DATA::ID => Some(Self::CANFD_FRAME(CANFD_FRAME_DATA::random(rng))),
34345 AVAILABLE_MODES_MONITOR_DATA::ID => Some(Self::AVAILABLE_MODES_MONITOR(
34346 AVAILABLE_MODES_MONITOR_DATA::random(rng),
34347 )),
34348 DEBUG_DATA::ID => Some(Self::DEBUG(DEBUG_DATA::random(rng))),
34349 CAN_FRAME_DATA::ID => Some(Self::CAN_FRAME(CAN_FRAME_DATA::random(rng))),
34350 MANUAL_SETPOINT_DATA::ID => {
34351 Some(Self::MANUAL_SETPOINT(MANUAL_SETPOINT_DATA::random(rng)))
34352 }
34353 MISSION_SET_CURRENT_DATA::ID => Some(Self::MISSION_SET_CURRENT(
34354 MISSION_SET_CURRENT_DATA::random(rng),
34355 )),
34356 BUTTON_CHANGE_DATA::ID => Some(Self::BUTTON_CHANGE(BUTTON_CHANGE_DATA::random(rng))),
34357 CAN_FILTER_MODIFY_DATA::ID => {
34358 Some(Self::CAN_FILTER_MODIFY(CAN_FILTER_MODIFY_DATA::random(rng)))
34359 }
34360 LOG_DATA_DATA::ID => Some(Self::LOG_DATA(LOG_DATA_DATA::random(rng))),
34361 DEBUG_VECT_DATA::ID => Some(Self::DEBUG_VECT(DEBUG_VECT_DATA::random(rng))),
34362 PLAY_TUNE_V2_DATA::ID => Some(Self::PLAY_TUNE_V2(PLAY_TUNE_V2_DATA::random(rng))),
34363 OPEN_DRONE_ID_SELF_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_SELF_ID(
34364 OPEN_DRONE_ID_SELF_ID_DATA::random(rng),
34365 )),
34366 COMMAND_CANCEL_DATA::ID => Some(Self::COMMAND_CANCEL(COMMAND_CANCEL_DATA::random(rng))),
34367 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CONTROL(
34368 UAVIONIX_ADSB_OUT_CONTROL_DATA::random(rng),
34369 )),
34370 RESPONSE_EVENT_ERROR_DATA::ID => Some(Self::RESPONSE_EVENT_ERROR(
34371 RESPONSE_EVENT_ERROR_DATA::random(rng),
34372 )),
34373 HEARTBEAT_DATA::ID => Some(Self::HEARTBEAT(HEARTBEAT_DATA::random(rng))),
34374 EVENT_DATA::ID => Some(Self::EVENT(EVENT_DATA::random(rng))),
34375 DEBUG_FLOAT_ARRAY_DATA::ID => {
34376 Some(Self::DEBUG_FLOAT_ARRAY(DEBUG_FLOAT_ARRAY_DATA::random(rng)))
34377 }
34378 COMMAND_INT_DATA::ID => Some(Self::COMMAND_INT(COMMAND_INT_DATA::random(rng))),
34379 FILE_TRANSFER_PROTOCOL_DATA::ID => Some(Self::FILE_TRANSFER_PROTOCOL(
34380 FILE_TRANSFER_PROTOCOL_DATA::random(rng),
34381 )),
34382 CELLULAR_STATUS_DATA::ID => {
34383 Some(Self::CELLULAR_STATUS(CELLULAR_STATUS_DATA::random(rng)))
34384 }
34385 REQUEST_DATA_STREAM_DATA::ID => Some(Self::REQUEST_DATA_STREAM(
34386 REQUEST_DATA_STREAM_DATA::random(rng),
34387 )),
34388 PARAM_EXT_REQUEST_LIST_DATA::ID => Some(Self::PARAM_EXT_REQUEST_LIST(
34389 PARAM_EXT_REQUEST_LIST_DATA::random(rng),
34390 )),
34391 WIND_COV_DATA::ID => Some(Self::WIND_COV(WIND_COV_DATA::random(rng))),
34392 ATTITUDE_DATA::ID => Some(Self::ATTITUDE(ATTITUDE_DATA::random(rng))),
34393 RADIO_STATUS_DATA::ID => Some(Self::RADIO_STATUS(RADIO_STATUS_DATA::random(rng))),
34394 NAMED_VALUE_FLOAT_DATA::ID => {
34395 Some(Self::NAMED_VALUE_FLOAT(NAMED_VALUE_FLOAT_DATA::random(rng)))
34396 }
34397 GPS_GLOBAL_ORIGIN_DATA::ID => {
34398 Some(Self::GPS_GLOBAL_ORIGIN(GPS_GLOBAL_ORIGIN_DATA::random(rng)))
34399 }
34400 POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::POSITION_TARGET_GLOBAL_INT(
34401 POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
34402 )),
34403 GPS_STATUS_DATA::ID => Some(Self::GPS_STATUS(GPS_STATUS_DATA::random(rng))),
34404 PARAM_REQUEST_LIST_DATA::ID => Some(Self::PARAM_REQUEST_LIST(
34405 PARAM_REQUEST_LIST_DATA::random(rng),
34406 )),
34407 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM_UPDATE(
34408 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::random(rng),
34409 )),
34410 FUEL_STATUS_DATA::ID => Some(Self::FUEL_STATUS(FUEL_STATUS_DATA::random(rng))),
34411 MEMORY_VECT_DATA::ID => Some(Self::MEMORY_VECT(MEMORY_VECT_DATA::random(rng))),
34412 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_DYNAMIC(
34413 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::random(rng),
34414 )),
34415 CAMERA_SETTINGS_DATA::ID => {
34416 Some(Self::CAMERA_SETTINGS(CAMERA_SETTINGS_DATA::random(rng)))
34417 }
34418 SERVO_OUTPUT_RAW_DATA::ID => {
34419 Some(Self::SERVO_OUTPUT_RAW(SERVO_OUTPUT_RAW_DATA::random(rng)))
34420 }
34421 ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::ACTUATOR_CONTROL_TARGET(
34422 ACTUATOR_CONTROL_TARGET_DATA::random(rng),
34423 )),
34424 ATTITUDE_TARGET_DATA::ID => {
34425 Some(Self::ATTITUDE_TARGET(ATTITUDE_TARGET_DATA::random(rng)))
34426 }
34427 SCALED_IMU_DATA::ID => Some(Self::SCALED_IMU(SCALED_IMU_DATA::random(rng))),
34428 STATUSTEXT_DATA::ID => Some(Self::STATUSTEXT(STATUSTEXT_DATA::random(rng))),
34429 ALTITUDE_DATA::ID => Some(Self::ALTITUDE(ALTITUDE_DATA::random(rng))),
34430 CHANGE_OPERATOR_CONTROL_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL(
34431 CHANGE_OPERATOR_CONTROL_DATA::random(rng),
34432 )),
34433 RAW_RPM_DATA::ID => Some(Self::RAW_RPM(RAW_RPM_DATA::random(rng))),
34434 GPS2_RTK_DATA::ID => Some(Self::GPS2_RTK(GPS2_RTK_DATA::random(rng))),
34435 OPTICAL_FLOW_DATA::ID => Some(Self::OPTICAL_FLOW(OPTICAL_FLOW_DATA::random(rng))),
34436 TERRAIN_DATA_DATA::ID => Some(Self::TERRAIN_DATA(TERRAIN_DATA_DATA::random(rng))),
34437 ORBIT_EXECUTION_STATUS_DATA::ID => Some(Self::ORBIT_EXECUTION_STATUS(
34438 ORBIT_EXECUTION_STATUS_DATA::random(rng),
34439 )),
34440 GLOBAL_POSITION_INT_DATA::ID => Some(Self::GLOBAL_POSITION_INT(
34441 GLOBAL_POSITION_INT_DATA::random(rng),
34442 )),
34443 TERRAIN_REPORT_DATA::ID => Some(Self::TERRAIN_REPORT(TERRAIN_REPORT_DATA::random(rng))),
34444 SAFETY_SET_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_SET_ALLOWED_AREA(
34445 SAFETY_SET_ALLOWED_AREA_DATA::random(rng),
34446 )),
34447 SET_HOME_POSITION_DATA::ID => {
34448 Some(Self::SET_HOME_POSITION(SET_HOME_POSITION_DATA::random(rng)))
34449 }
34450 AUTOPILOT_VERSION_DATA::ID => {
34451 Some(Self::AUTOPILOT_VERSION(AUTOPILOT_VERSION_DATA::random(rng)))
34452 }
34453 SETUP_SIGNING_DATA::ID => Some(Self::SETUP_SIGNING(SETUP_SIGNING_DATA::random(rng))),
34454 ILLUMINATOR_STATUS_DATA::ID => Some(Self::ILLUMINATOR_STATUS(
34455 ILLUMINATOR_STATUS_DATA::random(rng),
34456 )),
34457 UAVCAN_NODE_INFO_DATA::ID => {
34458 Some(Self::UAVCAN_NODE_INFO(UAVCAN_NODE_INFO_DATA::random(rng)))
34459 }
34460 GIMBAL_DEVICE_INFORMATION_DATA::ID => Some(Self::GIMBAL_DEVICE_INFORMATION(
34461 GIMBAL_DEVICE_INFORMATION_DATA::random(rng),
34462 )),
34463 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_ATTITUDE(
34464 GIMBAL_MANAGER_SET_ATTITUDE_DATA::random(rng),
34465 )),
34466 LOGGING_DATA_ACKED_DATA::ID => Some(Self::LOGGING_DATA_ACKED(
34467 LOGGING_DATA_ACKED_DATA::random(rng),
34468 )),
34469 RC_CHANNELS_RAW_DATA::ID => {
34470 Some(Self::RC_CHANNELS_RAW(RC_CHANNELS_RAW_DATA::random(rng)))
34471 }
34472 LINK_NODE_STATUS_DATA::ID => {
34473 Some(Self::LINK_NODE_STATUS(LINK_NODE_STATUS_DATA::random(rng)))
34474 }
34475 MISSION_ITEM_REACHED_DATA::ID => Some(Self::MISSION_ITEM_REACHED(
34476 MISSION_ITEM_REACHED_DATA::random(rng),
34477 )),
34478 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => Some(Self::SET_POSITION_TARGET_GLOBAL_INT(
34479 SET_POSITION_TARGET_GLOBAL_INT_DATA::random(rng),
34480 )),
34481 SMART_BATTERY_INFO_DATA::ID => Some(Self::SMART_BATTERY_INFO(
34482 SMART_BATTERY_INFO_DATA::random(rng),
34483 )),
34484 SET_GPS_GLOBAL_ORIGIN_DATA::ID => Some(Self::SET_GPS_GLOBAL_ORIGIN(
34485 SET_GPS_GLOBAL_ORIGIN_DATA::random(rng),
34486 )),
34487 VIBRATION_DATA::ID => Some(Self::VIBRATION(VIBRATION_DATA::random(rng))),
34488 GIMBAL_MANAGER_STATUS_DATA::ID => Some(Self::GIMBAL_MANAGER_STATUS(
34489 GIMBAL_MANAGER_STATUS_DATA::random(rng),
34490 )),
34491 MISSION_ITEM_INT_DATA::ID => {
34492 Some(Self::MISSION_ITEM_INT(MISSION_ITEM_INT_DATA::random(rng)))
34493 }
34494 POWER_STATUS_DATA::ID => Some(Self::POWER_STATUS(POWER_STATUS_DATA::random(rng))),
34495 LOGGING_DATA_DATA::ID => Some(Self::LOGGING_DATA(LOGGING_DATA_DATA::random(rng))),
34496 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => Some(Self::CHANGE_OPERATOR_CONTROL_ACK(
34497 CHANGE_OPERATOR_CONTROL_ACK_DATA::random(rng),
34498 )),
34499 GPS_RTK_DATA::ID => Some(Self::GPS_RTK(GPS_RTK_DATA::random(rng))),
34500 FLIGHT_INFORMATION_DATA::ID => Some(Self::FLIGHT_INFORMATION(
34501 FLIGHT_INFORMATION_DATA::random(rng),
34502 )),
34503 SUPPORTED_TUNES_DATA::ID => {
34504 Some(Self::SUPPORTED_TUNES(SUPPORTED_TUNES_DATA::random(rng)))
34505 }
34506 WIFI_CONFIG_AP_DATA::ID => Some(Self::WIFI_CONFIG_AP(WIFI_CONFIG_AP_DATA::random(rng))),
34507 TERRAIN_CHECK_DATA::ID => Some(Self::TERRAIN_CHECK(TERRAIN_CHECK_DATA::random(rng))),
34508 RAW_PRESSURE_DATA::ID => Some(Self::RAW_PRESSURE(RAW_PRESSURE_DATA::random(rng))),
34509 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => Some(Self::OPEN_DRONE_ID_AUTHENTICATION(
34510 OPEN_DRONE_ID_AUTHENTICATION_DATA::random(rng),
34511 )),
34512 ESC_INFO_DATA::ID => Some(Self::ESC_INFO(ESC_INFO_DATA::random(rng))),
34513 DISTANCE_SENSOR_DATA::ID => {
34514 Some(Self::DISTANCE_SENSOR(DISTANCE_SENSOR_DATA::random(rng)))
34515 }
34516 HIL_RC_INPUTS_RAW_DATA::ID => {
34517 Some(Self::HIL_RC_INPUTS_RAW(HIL_RC_INPUTS_RAW_DATA::random(rng)))
34518 }
34519 ISBD_LINK_STATUS_DATA::ID => {
34520 Some(Self::ISBD_LINK_STATUS(ISBD_LINK_STATUS_DATA::random(rng)))
34521 }
34522 RC_CHANNELS_SCALED_DATA::ID => Some(Self::RC_CHANNELS_SCALED(
34523 RC_CHANNELS_SCALED_DATA::random(rng),
34524 )),
34525 SCALED_IMU2_DATA::ID => Some(Self::SCALED_IMU2(SCALED_IMU2_DATA::random(rng))),
34526 HIL_SENSOR_DATA::ID => Some(Self::HIL_SENSOR(HIL_SENSOR_DATA::random(rng))),
34527 RESOURCE_REQUEST_DATA::ID => {
34528 Some(Self::RESOURCE_REQUEST(RESOURCE_REQUEST_DATA::random(rng)))
34529 }
34530 CAMERA_THERMAL_RANGE_DATA::ID => Some(Self::CAMERA_THERMAL_RANGE(
34531 CAMERA_THERMAL_RANGE_DATA::random(rng),
34532 )),
34533 TIMESYNC_DATA::ID => Some(Self::TIMESYNC(TIMESYNC_DATA::random(rng))),
34534 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => Some(Self::OPEN_DRONE_ID_MESSAGE_PACK(
34535 OPEN_DRONE_ID_MESSAGE_PACK_DATA::random(rng),
34536 )),
34537 LOG_REQUEST_DATA_DATA::ID => {
34538 Some(Self::LOG_REQUEST_DATA(LOG_REQUEST_DATA_DATA::random(rng)))
34539 }
34540 COMPONENT_METADATA_DATA::ID => Some(Self::COMPONENT_METADATA(
34541 COMPONENT_METADATA_DATA::random(rng),
34542 )),
34543 MAG_CAL_REPORT_DATA::ID => Some(Self::MAG_CAL_REPORT(MAG_CAL_REPORT_DATA::random(rng))),
34544 NAMED_VALUE_INT_DATA::ID => {
34545 Some(Self::NAMED_VALUE_INT(NAMED_VALUE_INT_DATA::random(rng)))
34546 }
34547 SAFETY_ALLOWED_AREA_DATA::ID => Some(Self::SAFETY_ALLOWED_AREA(
34548 SAFETY_ALLOWED_AREA_DATA::random(rng),
34549 )),
34550 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => Some(Self::GIMBAL_DEVICE_ATTITUDE_STATUS(
34551 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::random(rng),
34552 )),
34553 ESC_STATUS_DATA::ID => Some(Self::ESC_STATUS(ESC_STATUS_DATA::random(rng))),
34554 PARAM_EXT_REQUEST_READ_DATA::ID => Some(Self::PARAM_EXT_REQUEST_READ(
34555 PARAM_EXT_REQUEST_READ_DATA::random(rng),
34556 )),
34557 SCALED_IMU3_DATA::ID => Some(Self::SCALED_IMU3(SCALED_IMU3_DATA::random(rng))),
34558 ESTIMATOR_STATUS_DATA::ID => {
34559 Some(Self::ESTIMATOR_STATUS(ESTIMATOR_STATUS_DATA::random(rng)))
34560 }
34561 PARAM_EXT_ACK_DATA::ID => Some(Self::PARAM_EXT_ACK(PARAM_EXT_ACK_DATA::random(rng))),
34562 V2_EXTENSION_DATA::ID => Some(Self::V2_EXTENSION(V2_EXTENSION_DATA::random(rng))),
34563 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => Some(Self::SET_ACTUATOR_CONTROL_TARGET(
34564 SET_ACTUATOR_CONTROL_TARGET_DATA::random(rng),
34565 )),
34566 RC_CHANNELS_OVERRIDE_DATA::ID => Some(Self::RC_CHANNELS_OVERRIDE(
34567 RC_CHANNELS_OVERRIDE_DATA::random(rng),
34568 )),
34569 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => Some(Self::DATA_TRANSMISSION_HANDSHAKE(
34570 DATA_TRANSMISSION_HANDSHAKE_DATA::random(rng),
34571 )),
34572 LOCAL_POSITION_NED_DATA::ID => Some(Self::LOCAL_POSITION_NED(
34573 LOCAL_POSITION_NED_DATA::random(rng),
34574 )),
34575 EXTENDED_SYS_STATE_DATA::ID => Some(Self::EXTENDED_SYS_STATE(
34576 EXTENDED_SYS_STATE_DATA::random(rng),
34577 )),
34578 FENCE_STATUS_DATA::ID => Some(Self::FENCE_STATUS(FENCE_STATUS_DATA::random(rng))),
34579 ONBOARD_COMPUTER_STATUS_DATA::ID => Some(Self::ONBOARD_COMPUTER_STATUS(
34580 ONBOARD_COMPUTER_STATUS_DATA::random(rng),
34581 )),
34582 MISSION_REQUEST_LIST_DATA::ID => Some(Self::MISSION_REQUEST_LIST(
34583 MISSION_REQUEST_LIST_DATA::random(rng),
34584 )),
34585 MESSAGE_INTERVAL_DATA::ID => {
34586 Some(Self::MESSAGE_INTERVAL(MESSAGE_INTERVAL_DATA::random(rng)))
34587 }
34588 TERRAIN_REQUEST_DATA::ID => {
34589 Some(Self::TERRAIN_REQUEST(TERRAIN_REQUEST_DATA::random(rng)))
34590 }
34591 SCALED_PRESSURE3_DATA::ID => {
34592 Some(Self::SCALED_PRESSURE3(SCALED_PRESSURE3_DATA::random(rng)))
34593 }
34594 REQUEST_EVENT_DATA::ID => Some(Self::REQUEST_EVENT(REQUEST_EVENT_DATA::random(rng))),
34595 SET_ATTITUDE_TARGET_DATA::ID => Some(Self::SET_ATTITUDE_TARGET(
34596 SET_ATTITUDE_TARGET_DATA::random(rng),
34597 )),
34598 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::SET_POSITION_TARGET_LOCAL_NED(
34599 SET_POSITION_TARGET_LOCAL_NED_DATA::random(rng),
34600 )),
34601 LOGGING_ACK_DATA::ID => Some(Self::LOGGING_ACK(LOGGING_ACK_DATA::random(rng))),
34602 LOG_ERASE_DATA::ID => Some(Self::LOG_ERASE(LOG_ERASE_DATA::random(rng))),
34603 OPEN_DRONE_ID_LOCATION_DATA::ID => Some(Self::OPEN_DRONE_ID_LOCATION(
34604 OPEN_DRONE_ID_LOCATION_DATA::random(rng),
34605 )),
34606 UAVIONIX_ADSB_OUT_CFG_DATA::ID => Some(Self::UAVIONIX_ADSB_OUT_CFG(
34607 UAVIONIX_ADSB_OUT_CFG_DATA::random(rng),
34608 )),
34609 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
34610 Some(Self::TRAJECTORY_REPRESENTATION_BEZIER(
34611 TRAJECTORY_REPRESENTATION_BEZIER_DATA::random(rng),
34612 ))
34613 }
34614 SIM_STATE_DATA::ID => Some(Self::SIM_STATE(SIM_STATE_DATA::random(rng))),
34615 ODOMETRY_DATA::ID => Some(Self::ODOMETRY(ODOMETRY_DATA::random(rng))),
34616 VISION_POSITION_ESTIMATE_DATA::ID => Some(Self::VISION_POSITION_ESTIMATE(
34617 VISION_POSITION_ESTIMATE_DATA::random(rng),
34618 )),
34619 PARAM_REQUEST_READ_DATA::ID => Some(Self::PARAM_REQUEST_READ(
34620 PARAM_REQUEST_READ_DATA::random(rng),
34621 )),
34622 BATTERY_INFO_DATA::ID => Some(Self::BATTERY_INFO(BATTERY_INFO_DATA::random(rng))),
34623 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
34624 Some(Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(
34625 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::random(rng),
34626 ))
34627 }
34628 VIDEO_STREAM_STATUS_DATA::ID => Some(Self::VIDEO_STREAM_STATUS(
34629 VIDEO_STREAM_STATUS_DATA::random(rng),
34630 )),
34631 ATT_POS_MOCAP_DATA::ID => Some(Self::ATT_POS_MOCAP(ATT_POS_MOCAP_DATA::random(rng))),
34632 UAVIONIX_ADSB_GET_DATA::ID => {
34633 Some(Self::UAVIONIX_ADSB_GET(UAVIONIX_ADSB_GET_DATA::random(rng)))
34634 }
34635 MISSION_ITEM_DATA::ID => Some(Self::MISSION_ITEM(MISSION_ITEM_DATA::random(rng))),
34636 VISION_SPEED_ESTIMATE_DATA::ID => Some(Self::VISION_SPEED_ESTIMATE(
34637 VISION_SPEED_ESTIMATE_DATA::random(rng),
34638 )),
34639 MISSION_WRITE_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_WRITE_PARTIAL_LIST(
34640 MISSION_WRITE_PARTIAL_LIST_DATA::random(rng),
34641 )),
34642 VFR_HUD_DATA::ID => Some(Self::VFR_HUD(VFR_HUD_DATA::random(rng))),
34643 POSITION_TARGET_LOCAL_NED_DATA::ID => Some(Self::POSITION_TARGET_LOCAL_NED(
34644 POSITION_TARGET_LOCAL_NED_DATA::random(rng),
34645 )),
34646 MISSION_CLEAR_ALL_DATA::ID => {
34647 Some(Self::MISSION_CLEAR_ALL(MISSION_CLEAR_ALL_DATA::random(rng)))
34648 }
34649 MANUAL_CONTROL_DATA::ID => Some(Self::MANUAL_CONTROL(MANUAL_CONTROL_DATA::random(rng))),
34650 AVAILABLE_MODES_DATA::ID => {
34651 Some(Self::AVAILABLE_MODES(AVAILABLE_MODES_DATA::random(rng)))
34652 }
34653 TIME_ESTIMATE_TO_TARGET_DATA::ID => Some(Self::TIME_ESTIMATE_TO_TARGET(
34654 TIME_ESTIMATE_TO_TARGET_DATA::random(rng),
34655 )),
34656 GPS_RAW_INT_DATA::ID => Some(Self::GPS_RAW_INT(GPS_RAW_INT_DATA::random(rng))),
34657 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
34658 Some(Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(
34659 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::random(rng),
34660 ))
34661 }
34662 VICON_POSITION_ESTIMATE_DATA::ID => Some(Self::VICON_POSITION_ESTIMATE(
34663 VICON_POSITION_ESTIMATE_DATA::random(rng),
34664 )),
34665 SCALED_PRESSURE2_DATA::ID => {
34666 Some(Self::SCALED_PRESSURE2(SCALED_PRESSURE2_DATA::random(rng)))
34667 }
34668 CONTROL_SYSTEM_STATE_DATA::ID => Some(Self::CONTROL_SYSTEM_STATE(
34669 CONTROL_SYSTEM_STATE_DATA::random(rng),
34670 )),
34671 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => Some(Self::MISSION_REQUEST_PARTIAL_LIST(
34672 MISSION_REQUEST_PARTIAL_LIST_DATA::random(rng),
34673 )),
34674 HOME_POSITION_DATA::ID => Some(Self::HOME_POSITION(HOME_POSITION_DATA::random(rng))),
34675 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => Some(Self::CAMERA_TRACKING_IMAGE_STATUS(
34676 CAMERA_TRACKING_IMAGE_STATUS_DATA::random(rng),
34677 )),
34678 ACTUATOR_OUTPUT_STATUS_DATA::ID => Some(Self::ACTUATOR_OUTPUT_STATUS(
34679 ACTUATOR_OUTPUT_STATUS_DATA::random(rng),
34680 )),
34681 LOG_REQUEST_END_DATA::ID => {
34682 Some(Self::LOG_REQUEST_END(LOG_REQUEST_END_DATA::random(rng)))
34683 }
34684 RC_CHANNELS_DATA::ID => Some(Self::RC_CHANNELS(RC_CHANNELS_DATA::random(rng))),
34685 ATTITUDE_QUATERNION_COV_DATA::ID => Some(Self::ATTITUDE_QUATERNION_COV(
34686 ATTITUDE_QUATERNION_COV_DATA::random(rng),
34687 )),
34688 CAMERA_TRIGGER_DATA::ID => Some(Self::CAMERA_TRIGGER(CAMERA_TRIGGER_DATA::random(rng))),
34689 FOLLOW_TARGET_DATA::ID => Some(Self::FOLLOW_TARGET(FOLLOW_TARGET_DATA::random(rng))),
34690 GLOBAL_POSITION_INT_COV_DATA::ID => Some(Self::GLOBAL_POSITION_INT_COV(
34691 GLOBAL_POSITION_INT_COV_DATA::random(rng),
34692 )),
34693 MOUNT_ORIENTATION_DATA::ID => {
34694 Some(Self::MOUNT_ORIENTATION(MOUNT_ORIENTATION_DATA::random(rng)))
34695 }
34696 GENERATOR_STATUS_DATA::ID => {
34697 Some(Self::GENERATOR_STATUS(GENERATOR_STATUS_DATA::random(rng)))
34698 }
34699 GPS_RTCM_DATA_DATA::ID => Some(Self::GPS_RTCM_DATA(GPS_RTCM_DATA_DATA::random(rng))),
34700 NAV_CONTROLLER_OUTPUT_DATA::ID => Some(Self::NAV_CONTROLLER_OUTPUT(
34701 NAV_CONTROLLER_OUTPUT_DATA::random(rng),
34702 )),
34703 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
34704 Some(Self::GLOBAL_VISION_POSITION_ESTIMATE(
34705 GLOBAL_VISION_POSITION_ESTIMATE_DATA::random(rng),
34706 ))
34707 }
34708 PARAM_EXT_VALUE_DATA::ID => {
34709 Some(Self::PARAM_EXT_VALUE(PARAM_EXT_VALUE_DATA::random(rng)))
34710 }
34711 CAMERA_CAPTURE_STATUS_DATA::ID => Some(Self::CAMERA_CAPTURE_STATUS(
34712 CAMERA_CAPTURE_STATUS_DATA::random(rng),
34713 )),
34714 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
34715 Some(Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(
34716 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::random(rng),
34717 ))
34718 }
34719 GIMBAL_MANAGER_INFORMATION_DATA::ID => Some(Self::GIMBAL_MANAGER_INFORMATION(
34720 GIMBAL_MANAGER_INFORMATION_DATA::random(rng),
34721 )),
34722 HIGH_LATENCY2_DATA::ID => Some(Self::HIGH_LATENCY2(HIGH_LATENCY2_DATA::random(rng))),
34723 HIGHRES_IMU_DATA::ID => Some(Self::HIGHRES_IMU(HIGHRES_IMU_DATA::random(rng))),
34724 HIL_CONTROLS_DATA::ID => Some(Self::HIL_CONTROLS(HIL_CONTROLS_DATA::random(rng))),
34725 MISSION_REQUEST_DATA::ID => {
34726 Some(Self::MISSION_REQUEST(MISSION_REQUEST_DATA::random(rng)))
34727 }
34728 LANDING_TARGET_DATA::ID => Some(Self::LANDING_TARGET(LANDING_TARGET_DATA::random(rng))),
34729 LOG_REQUEST_LIST_DATA::ID => {
34730 Some(Self::LOG_REQUEST_LIST(LOG_REQUEST_LIST_DATA::random(rng)))
34731 }
34732 CAMERA_FOV_STATUS_DATA::ID => {
34733 Some(Self::CAMERA_FOV_STATUS(CAMERA_FOV_STATUS_DATA::random(rng)))
34734 }
34735 LOG_ENTRY_DATA::ID => Some(Self::LOG_ENTRY(LOG_ENTRY_DATA::random(rng))),
34736 GPS_INJECT_DATA_DATA::ID => {
34737 Some(Self::GPS_INJECT_DATA(GPS_INJECT_DATA_DATA::random(rng)))
34738 }
34739 PARAM_VALUE_DATA::ID => Some(Self::PARAM_VALUE(PARAM_VALUE_DATA::random(rng))),
34740 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => Some(Self::GIMBAL_MANAGER_SET_PITCHYAW(
34741 GIMBAL_MANAGER_SET_PITCHYAW_DATA::random(rng),
34742 )),
34743 CURRENT_EVENT_SEQUENCE_DATA::ID => Some(Self::CURRENT_EVENT_SEQUENCE(
34744 CURRENT_EVENT_SEQUENCE_DATA::random(rng),
34745 )),
34746 CAMERA_INFORMATION_DATA::ID => Some(Self::CAMERA_INFORMATION(
34747 CAMERA_INFORMATION_DATA::random(rng),
34748 )),
34749 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => Some(Self::OPEN_DRONE_ID_OPERATOR_ID(
34750 OPEN_DRONE_ID_OPERATOR_ID_DATA::random(rng),
34751 )),
34752 COMPONENT_INFORMATION_DATA::ID => Some(Self::COMPONENT_INFORMATION(
34753 COMPONENT_INFORMATION_DATA::random(rng),
34754 )),
34755 COMMAND_LONG_DATA::ID => Some(Self::COMMAND_LONG(COMMAND_LONG_DATA::random(rng))),
34756 PARAM_EXT_SET_DATA::ID => Some(Self::PARAM_EXT_SET(PARAM_EXT_SET_DATA::random(rng))),
34757 GPS_INPUT_DATA::ID => Some(Self::GPS_INPUT(GPS_INPUT_DATA::random(rng))),
34758 SET_MODE_DATA::ID => Some(Self::SET_MODE(SET_MODE_DATA::random(rng))),
34759 AIS_VESSEL_DATA::ID => Some(Self::AIS_VESSEL(AIS_VESSEL_DATA::random(rng))),
34760 ATTITUDE_QUATERNION_DATA::ID => Some(Self::ATTITUDE_QUATERNION(
34761 ATTITUDE_QUATERNION_DATA::random(rng),
34762 )),
34763 CURRENT_MODE_DATA::ID => Some(Self::CURRENT_MODE(CURRENT_MODE_DATA::random(rng))),
34764 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => Some(Self::GIMBAL_DEVICE_SET_ATTITUDE(
34765 GIMBAL_DEVICE_SET_ATTITUDE_DATA::random(rng),
34766 )),
34767 HYGROMETER_SENSOR_DATA::ID => {
34768 Some(Self::HYGROMETER_SENSOR(HYGROMETER_SENSOR_DATA::random(rng)))
34769 }
34770 PARAM_MAP_RC_DATA::ID => Some(Self::PARAM_MAP_RC(PARAM_MAP_RC_DATA::random(rng))),
34771 COMPONENT_INFORMATION_BASIC_DATA::ID => Some(Self::COMPONENT_INFORMATION_BASIC(
34772 COMPONENT_INFORMATION_BASIC_DATA::random(rng),
34773 )),
34774 OPEN_DRONE_ID_SYSTEM_DATA::ID => Some(Self::OPEN_DRONE_ID_SYSTEM(
34775 OPEN_DRONE_ID_SYSTEM_DATA::random(rng),
34776 )),
34777 COMMAND_ACK_DATA::ID => Some(Self::COMMAND_ACK(COMMAND_ACK_DATA::random(rng))),
34778 SERIAL_CONTROL_DATA::ID => Some(Self::SERIAL_CONTROL(SERIAL_CONTROL_DATA::random(rng))),
34779 _ => None,
34780 }
34781 }
34782 fn ser(&self, version: MavlinkVersion, bytes: &mut [u8]) -> usize {
34783 match self {
34784 Self::MISSION_COUNT(body) => body.ser(version, bytes),
34785 Self::SYSTEM_TIME(body) => body.ser(version, bytes),
34786 Self::SYS_STATUS(body) => body.ser(version, bytes),
34787 Self::ADSB_VEHICLE(body) => body.ser(version, bytes),
34788 Self::TUNNEL(body) => body.ser(version, bytes),
34789 Self::OPEN_DRONE_ID_ARM_STATUS(body) => body.ser(version, bytes),
34790 Self::RAW_IMU(body) => body.ser(version, bytes),
34791 Self::MISSION_CURRENT(body) => body.ser(version, bytes),
34792 Self::HIL_STATE(body) => body.ser(version, bytes),
34793 Self::OBSTACLE_DISTANCE(body) => body.ser(version, bytes),
34794 Self::TRAJECTORY_REPRESENTATION_WAYPOINTS(body) => body.ser(version, bytes),
34795 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(body) => body.ser(version, bytes),
34796 Self::CAMERA_IMAGE_CAPTURED(body) => body.ser(version, bytes),
34797 Self::PROTOCOL_VERSION(body) => body.ser(version, bytes),
34798 Self::GPS2_RAW(body) => body.ser(version, bytes),
34799 Self::UTM_GLOBAL_POSITION(body) => body.ser(version, bytes),
34800 Self::HIL_GPS(body) => body.ser(version, bytes),
34801 Self::HIGH_LATENCY(body) => body.ser(version, bytes),
34802 Self::OPEN_DRONE_ID_BASIC_ID(body) => body.ser(version, bytes),
34803 Self::BATTERY_STATUS(body) => body.ser(version, bytes),
34804 Self::EFI_STATUS(body) => body.ser(version, bytes),
34805 Self::WINCH_STATUS(body) => body.ser(version, bytes),
34806 Self::UAVIONIX_ADSB_OUT_CFG_FLIGHTID(body) => body.ser(version, bytes),
34807 Self::PING(body) => body.ser(version, bytes),
34808 Self::HIL_OPTICAL_FLOW(body) => body.ser(version, bytes),
34809 Self::VIDEO_STREAM_INFORMATION(body) => body.ser(version, bytes),
34810 Self::LOCAL_POSITION_NED_COV(body) => body.ser(version, bytes),
34811 Self::AUTH_KEY(body) => body.ser(version, bytes),
34812 Self::HIL_ACTUATOR_CONTROLS(body) => body.ser(version, bytes),
34813 Self::COLLISION(body) => body.ser(version, bytes),
34814 Self::UAVIONIX_ADSB_OUT_CFG_REGISTRATION(body) => body.ser(version, bytes),
34815 Self::HIL_STATE_QUATERNION(body) => body.ser(version, bytes),
34816 Self::UAVIONIX_ADSB_OUT_STATUS(body) => body.ser(version, bytes),
34817 Self::MISSION_ACK(body) => body.ser(version, bytes),
34818 Self::WHEEL_DISTANCE(body) => body.ser(version, bytes),
34819 Self::OPTICAL_FLOW_RAD(body) => body.ser(version, bytes),
34820 Self::CAMERA_TRACKING_GEO_STATUS(body) => body.ser(version, bytes),
34821 Self::CELLULAR_CONFIG(body) => body.ser(version, bytes),
34822 Self::DATA_STREAM(body) => body.ser(version, bytes),
34823 Self::PARAM_SET(body) => body.ser(version, bytes),
34824 Self::UAVCAN_NODE_STATUS(body) => body.ser(version, bytes),
34825 Self::STORAGE_INFORMATION(body) => body.ser(version, bytes),
34826 Self::MISSION_REQUEST_INT(body) => body.ser(version, bytes),
34827 Self::SCALED_PRESSURE(body) => body.ser(version, bytes),
34828 Self::ENCAPSULATED_DATA(body) => body.ser(version, bytes),
34829 Self::PLAY_TUNE(body) => body.ser(version, bytes),
34830 Self::CANFD_FRAME(body) => body.ser(version, bytes),
34831 Self::AVAILABLE_MODES_MONITOR(body) => body.ser(version, bytes),
34832 Self::DEBUG(body) => body.ser(version, bytes),
34833 Self::CAN_FRAME(body) => body.ser(version, bytes),
34834 Self::MANUAL_SETPOINT(body) => body.ser(version, bytes),
34835 Self::MISSION_SET_CURRENT(body) => body.ser(version, bytes),
34836 Self::BUTTON_CHANGE(body) => body.ser(version, bytes),
34837 Self::CAN_FILTER_MODIFY(body) => body.ser(version, bytes),
34838 Self::LOG_DATA(body) => body.ser(version, bytes),
34839 Self::DEBUG_VECT(body) => body.ser(version, bytes),
34840 Self::PLAY_TUNE_V2(body) => body.ser(version, bytes),
34841 Self::OPEN_DRONE_ID_SELF_ID(body) => body.ser(version, bytes),
34842 Self::COMMAND_CANCEL(body) => body.ser(version, bytes),
34843 Self::UAVIONIX_ADSB_OUT_CONTROL(body) => body.ser(version, bytes),
34844 Self::RESPONSE_EVENT_ERROR(body) => body.ser(version, bytes),
34845 Self::HEARTBEAT(body) => body.ser(version, bytes),
34846 Self::EVENT(body) => body.ser(version, bytes),
34847 Self::DEBUG_FLOAT_ARRAY(body) => body.ser(version, bytes),
34848 Self::COMMAND_INT(body) => body.ser(version, bytes),
34849 Self::FILE_TRANSFER_PROTOCOL(body) => body.ser(version, bytes),
34850 Self::CELLULAR_STATUS(body) => body.ser(version, bytes),
34851 Self::REQUEST_DATA_STREAM(body) => body.ser(version, bytes),
34852 Self::PARAM_EXT_REQUEST_LIST(body) => body.ser(version, bytes),
34853 Self::WIND_COV(body) => body.ser(version, bytes),
34854 Self::ATTITUDE(body) => body.ser(version, bytes),
34855 Self::RADIO_STATUS(body) => body.ser(version, bytes),
34856 Self::NAMED_VALUE_FLOAT(body) => body.ser(version, bytes),
34857 Self::GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
34858 Self::POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
34859 Self::GPS_STATUS(body) => body.ser(version, bytes),
34860 Self::PARAM_REQUEST_LIST(body) => body.ser(version, bytes),
34861 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(body) => body.ser(version, bytes),
34862 Self::FUEL_STATUS(body) => body.ser(version, bytes),
34863 Self::MEMORY_VECT(body) => body.ser(version, bytes),
34864 Self::UAVIONIX_ADSB_OUT_DYNAMIC(body) => body.ser(version, bytes),
34865 Self::CAMERA_SETTINGS(body) => body.ser(version, bytes),
34866 Self::SERVO_OUTPUT_RAW(body) => body.ser(version, bytes),
34867 Self::ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
34868 Self::ATTITUDE_TARGET(body) => body.ser(version, bytes),
34869 Self::SCALED_IMU(body) => body.ser(version, bytes),
34870 Self::STATUSTEXT(body) => body.ser(version, bytes),
34871 Self::ALTITUDE(body) => body.ser(version, bytes),
34872 Self::CHANGE_OPERATOR_CONTROL(body) => body.ser(version, bytes),
34873 Self::RAW_RPM(body) => body.ser(version, bytes),
34874 Self::GPS2_RTK(body) => body.ser(version, bytes),
34875 Self::OPTICAL_FLOW(body) => body.ser(version, bytes),
34876 Self::TERRAIN_DATA(body) => body.ser(version, bytes),
34877 Self::ORBIT_EXECUTION_STATUS(body) => body.ser(version, bytes),
34878 Self::GLOBAL_POSITION_INT(body) => body.ser(version, bytes),
34879 Self::TERRAIN_REPORT(body) => body.ser(version, bytes),
34880 Self::SAFETY_SET_ALLOWED_AREA(body) => body.ser(version, bytes),
34881 Self::SET_HOME_POSITION(body) => body.ser(version, bytes),
34882 Self::AUTOPILOT_VERSION(body) => body.ser(version, bytes),
34883 Self::SETUP_SIGNING(body) => body.ser(version, bytes),
34884 Self::ILLUMINATOR_STATUS(body) => body.ser(version, bytes),
34885 Self::UAVCAN_NODE_INFO(body) => body.ser(version, bytes),
34886 Self::GIMBAL_DEVICE_INFORMATION(body) => body.ser(version, bytes),
34887 Self::GIMBAL_MANAGER_SET_ATTITUDE(body) => body.ser(version, bytes),
34888 Self::LOGGING_DATA_ACKED(body) => body.ser(version, bytes),
34889 Self::RC_CHANNELS_RAW(body) => body.ser(version, bytes),
34890 Self::LINK_NODE_STATUS(body) => body.ser(version, bytes),
34891 Self::MISSION_ITEM_REACHED(body) => body.ser(version, bytes),
34892 Self::SET_POSITION_TARGET_GLOBAL_INT(body) => body.ser(version, bytes),
34893 Self::SMART_BATTERY_INFO(body) => body.ser(version, bytes),
34894 Self::SET_GPS_GLOBAL_ORIGIN(body) => body.ser(version, bytes),
34895 Self::VIBRATION(body) => body.ser(version, bytes),
34896 Self::GIMBAL_MANAGER_STATUS(body) => body.ser(version, bytes),
34897 Self::MISSION_ITEM_INT(body) => body.ser(version, bytes),
34898 Self::POWER_STATUS(body) => body.ser(version, bytes),
34899 Self::LOGGING_DATA(body) => body.ser(version, bytes),
34900 Self::CHANGE_OPERATOR_CONTROL_ACK(body) => body.ser(version, bytes),
34901 Self::GPS_RTK(body) => body.ser(version, bytes),
34902 Self::FLIGHT_INFORMATION(body) => body.ser(version, bytes),
34903 Self::SUPPORTED_TUNES(body) => body.ser(version, bytes),
34904 Self::WIFI_CONFIG_AP(body) => body.ser(version, bytes),
34905 Self::TERRAIN_CHECK(body) => body.ser(version, bytes),
34906 Self::RAW_PRESSURE(body) => body.ser(version, bytes),
34907 Self::OPEN_DRONE_ID_AUTHENTICATION(body) => body.ser(version, bytes),
34908 Self::ESC_INFO(body) => body.ser(version, bytes),
34909 Self::DISTANCE_SENSOR(body) => body.ser(version, bytes),
34910 Self::HIL_RC_INPUTS_RAW(body) => body.ser(version, bytes),
34911 Self::ISBD_LINK_STATUS(body) => body.ser(version, bytes),
34912 Self::RC_CHANNELS_SCALED(body) => body.ser(version, bytes),
34913 Self::SCALED_IMU2(body) => body.ser(version, bytes),
34914 Self::HIL_SENSOR(body) => body.ser(version, bytes),
34915 Self::RESOURCE_REQUEST(body) => body.ser(version, bytes),
34916 Self::CAMERA_THERMAL_RANGE(body) => body.ser(version, bytes),
34917 Self::TIMESYNC(body) => body.ser(version, bytes),
34918 Self::OPEN_DRONE_ID_MESSAGE_PACK(body) => body.ser(version, bytes),
34919 Self::LOG_REQUEST_DATA(body) => body.ser(version, bytes),
34920 Self::COMPONENT_METADATA(body) => body.ser(version, bytes),
34921 Self::MAG_CAL_REPORT(body) => body.ser(version, bytes),
34922 Self::NAMED_VALUE_INT(body) => body.ser(version, bytes),
34923 Self::SAFETY_ALLOWED_AREA(body) => body.ser(version, bytes),
34924 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(body) => body.ser(version, bytes),
34925 Self::ESC_STATUS(body) => body.ser(version, bytes),
34926 Self::PARAM_EXT_REQUEST_READ(body) => body.ser(version, bytes),
34927 Self::SCALED_IMU3(body) => body.ser(version, bytes),
34928 Self::ESTIMATOR_STATUS(body) => body.ser(version, bytes),
34929 Self::PARAM_EXT_ACK(body) => body.ser(version, bytes),
34930 Self::V2_EXTENSION(body) => body.ser(version, bytes),
34931 Self::SET_ACTUATOR_CONTROL_TARGET(body) => body.ser(version, bytes),
34932 Self::RC_CHANNELS_OVERRIDE(body) => body.ser(version, bytes),
34933 Self::DATA_TRANSMISSION_HANDSHAKE(body) => body.ser(version, bytes),
34934 Self::LOCAL_POSITION_NED(body) => body.ser(version, bytes),
34935 Self::EXTENDED_SYS_STATE(body) => body.ser(version, bytes),
34936 Self::FENCE_STATUS(body) => body.ser(version, bytes),
34937 Self::ONBOARD_COMPUTER_STATUS(body) => body.ser(version, bytes),
34938 Self::MISSION_REQUEST_LIST(body) => body.ser(version, bytes),
34939 Self::MESSAGE_INTERVAL(body) => body.ser(version, bytes),
34940 Self::TERRAIN_REQUEST(body) => body.ser(version, bytes),
34941 Self::SCALED_PRESSURE3(body) => body.ser(version, bytes),
34942 Self::REQUEST_EVENT(body) => body.ser(version, bytes),
34943 Self::SET_ATTITUDE_TARGET(body) => body.ser(version, bytes),
34944 Self::SET_POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
34945 Self::LOGGING_ACK(body) => body.ser(version, bytes),
34946 Self::LOG_ERASE(body) => body.ser(version, bytes),
34947 Self::OPEN_DRONE_ID_LOCATION(body) => body.ser(version, bytes),
34948 Self::UAVIONIX_ADSB_OUT_CFG(body) => body.ser(version, bytes),
34949 Self::TRAJECTORY_REPRESENTATION_BEZIER(body) => body.ser(version, bytes),
34950 Self::SIM_STATE(body) => body.ser(version, bytes),
34951 Self::ODOMETRY(body) => body.ser(version, bytes),
34952 Self::VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
34953 Self::PARAM_REQUEST_READ(body) => body.ser(version, bytes),
34954 Self::BATTERY_INFO(body) => body.ser(version, bytes),
34955 Self::LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET(body) => body.ser(version, bytes),
34956 Self::VIDEO_STREAM_STATUS(body) => body.ser(version, bytes),
34957 Self::ATT_POS_MOCAP(body) => body.ser(version, bytes),
34958 Self::UAVIONIX_ADSB_GET(body) => body.ser(version, bytes),
34959 Self::MISSION_ITEM(body) => body.ser(version, bytes),
34960 Self::VISION_SPEED_ESTIMATE(body) => body.ser(version, bytes),
34961 Self::MISSION_WRITE_PARTIAL_LIST(body) => body.ser(version, bytes),
34962 Self::VFR_HUD(body) => body.ser(version, bytes),
34963 Self::POSITION_TARGET_LOCAL_NED(body) => body.ser(version, bytes),
34964 Self::MISSION_CLEAR_ALL(body) => body.ser(version, bytes),
34965 Self::MANUAL_CONTROL(body) => body.ser(version, bytes),
34966 Self::AVAILABLE_MODES(body) => body.ser(version, bytes),
34967 Self::TIME_ESTIMATE_TO_TARGET(body) => body.ser(version, bytes),
34968 Self::GPS_RAW_INT(body) => body.ser(version, bytes),
34969 Self::UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT(body) => body.ser(version, bytes),
34970 Self::VICON_POSITION_ESTIMATE(body) => body.ser(version, bytes),
34971 Self::SCALED_PRESSURE2(body) => body.ser(version, bytes),
34972 Self::CONTROL_SYSTEM_STATE(body) => body.ser(version, bytes),
34973 Self::MISSION_REQUEST_PARTIAL_LIST(body) => body.ser(version, bytes),
34974 Self::HOME_POSITION(body) => body.ser(version, bytes),
34975 Self::CAMERA_TRACKING_IMAGE_STATUS(body) => body.ser(version, bytes),
34976 Self::ACTUATOR_OUTPUT_STATUS(body) => body.ser(version, bytes),
34977 Self::LOG_REQUEST_END(body) => body.ser(version, bytes),
34978 Self::RC_CHANNELS(body) => body.ser(version, bytes),
34979 Self::ATTITUDE_QUATERNION_COV(body) => body.ser(version, bytes),
34980 Self::CAMERA_TRIGGER(body) => body.ser(version, bytes),
34981 Self::FOLLOW_TARGET(body) => body.ser(version, bytes),
34982 Self::GLOBAL_POSITION_INT_COV(body) => body.ser(version, bytes),
34983 Self::MOUNT_ORIENTATION(body) => body.ser(version, bytes),
34984 Self::GENERATOR_STATUS(body) => body.ser(version, bytes),
34985 Self::GPS_RTCM_DATA(body) => body.ser(version, bytes),
34986 Self::NAV_CONTROLLER_OUTPUT(body) => body.ser(version, bytes),
34987 Self::GLOBAL_VISION_POSITION_ESTIMATE(body) => body.ser(version, bytes),
34988 Self::PARAM_EXT_VALUE(body) => body.ser(version, bytes),
34989 Self::CAMERA_CAPTURE_STATUS(body) => body.ser(version, bytes),
34990 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(body) => body.ser(version, bytes),
34991 Self::GIMBAL_MANAGER_INFORMATION(body) => body.ser(version, bytes),
34992 Self::HIGH_LATENCY2(body) => body.ser(version, bytes),
34993 Self::HIGHRES_IMU(body) => body.ser(version, bytes),
34994 Self::HIL_CONTROLS(body) => body.ser(version, bytes),
34995 Self::MISSION_REQUEST(body) => body.ser(version, bytes),
34996 Self::LANDING_TARGET(body) => body.ser(version, bytes),
34997 Self::LOG_REQUEST_LIST(body) => body.ser(version, bytes),
34998 Self::CAMERA_FOV_STATUS(body) => body.ser(version, bytes),
34999 Self::LOG_ENTRY(body) => body.ser(version, bytes),
35000 Self::GPS_INJECT_DATA(body) => body.ser(version, bytes),
35001 Self::PARAM_VALUE(body) => body.ser(version, bytes),
35002 Self::GIMBAL_MANAGER_SET_PITCHYAW(body) => body.ser(version, bytes),
35003 Self::CURRENT_EVENT_SEQUENCE(body) => body.ser(version, bytes),
35004 Self::CAMERA_INFORMATION(body) => body.ser(version, bytes),
35005 Self::OPEN_DRONE_ID_OPERATOR_ID(body) => body.ser(version, bytes),
35006 Self::COMPONENT_INFORMATION(body) => body.ser(version, bytes),
35007 Self::COMMAND_LONG(body) => body.ser(version, bytes),
35008 Self::PARAM_EXT_SET(body) => body.ser(version, bytes),
35009 Self::GPS_INPUT(body) => body.ser(version, bytes),
35010 Self::SET_MODE(body) => body.ser(version, bytes),
35011 Self::AIS_VESSEL(body) => body.ser(version, bytes),
35012 Self::ATTITUDE_QUATERNION(body) => body.ser(version, bytes),
35013 Self::CURRENT_MODE(body) => body.ser(version, bytes),
35014 Self::GIMBAL_DEVICE_SET_ATTITUDE(body) => body.ser(version, bytes),
35015 Self::HYGROMETER_SENSOR(body) => body.ser(version, bytes),
35016 Self::PARAM_MAP_RC(body) => body.ser(version, bytes),
35017 Self::COMPONENT_INFORMATION_BASIC(body) => body.ser(version, bytes),
35018 Self::OPEN_DRONE_ID_SYSTEM(body) => body.ser(version, bytes),
35019 Self::COMMAND_ACK(body) => body.ser(version, bytes),
35020 Self::SERIAL_CONTROL(body) => body.ser(version, bytes),
35021 }
35022 }
35023 fn extra_crc(id: u32) -> u8 {
35024 match id {
35025 MISSION_COUNT_DATA::ID => MISSION_COUNT_DATA::EXTRA_CRC,
35026 SYSTEM_TIME_DATA::ID => SYSTEM_TIME_DATA::EXTRA_CRC,
35027 SYS_STATUS_DATA::ID => SYS_STATUS_DATA::EXTRA_CRC,
35028 ADSB_VEHICLE_DATA::ID => ADSB_VEHICLE_DATA::EXTRA_CRC,
35029 TUNNEL_DATA::ID => TUNNEL_DATA::EXTRA_CRC,
35030 OPEN_DRONE_ID_ARM_STATUS_DATA::ID => OPEN_DRONE_ID_ARM_STATUS_DATA::EXTRA_CRC,
35031 RAW_IMU_DATA::ID => RAW_IMU_DATA::EXTRA_CRC,
35032 MISSION_CURRENT_DATA::ID => MISSION_CURRENT_DATA::EXTRA_CRC,
35033 HIL_STATE_DATA::ID => HIL_STATE_DATA::EXTRA_CRC,
35034 OBSTACLE_DISTANCE_DATA::ID => OBSTACLE_DISTANCE_DATA::EXTRA_CRC,
35035 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::ID => {
35036 TRAJECTORY_REPRESENTATION_WAYPOINTS_DATA::EXTRA_CRC
35037 }
35038 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::ID => {
35039 AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_DATA::EXTRA_CRC
35040 }
35041 CAMERA_IMAGE_CAPTURED_DATA::ID => CAMERA_IMAGE_CAPTURED_DATA::EXTRA_CRC,
35042 PROTOCOL_VERSION_DATA::ID => PROTOCOL_VERSION_DATA::EXTRA_CRC,
35043 GPS2_RAW_DATA::ID => GPS2_RAW_DATA::EXTRA_CRC,
35044 UTM_GLOBAL_POSITION_DATA::ID => UTM_GLOBAL_POSITION_DATA::EXTRA_CRC,
35045 HIL_GPS_DATA::ID => HIL_GPS_DATA::EXTRA_CRC,
35046 HIGH_LATENCY_DATA::ID => HIGH_LATENCY_DATA::EXTRA_CRC,
35047 OPEN_DRONE_ID_BASIC_ID_DATA::ID => OPEN_DRONE_ID_BASIC_ID_DATA::EXTRA_CRC,
35048 BATTERY_STATUS_DATA::ID => BATTERY_STATUS_DATA::EXTRA_CRC,
35049 EFI_STATUS_DATA::ID => EFI_STATUS_DATA::EXTRA_CRC,
35050 WINCH_STATUS_DATA::ID => WINCH_STATUS_DATA::EXTRA_CRC,
35051 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::ID => {
35052 UAVIONIX_ADSB_OUT_CFG_FLIGHTID_DATA::EXTRA_CRC
35053 }
35054 PING_DATA::ID => PING_DATA::EXTRA_CRC,
35055 HIL_OPTICAL_FLOW_DATA::ID => HIL_OPTICAL_FLOW_DATA::EXTRA_CRC,
35056 VIDEO_STREAM_INFORMATION_DATA::ID => VIDEO_STREAM_INFORMATION_DATA::EXTRA_CRC,
35057 LOCAL_POSITION_NED_COV_DATA::ID => LOCAL_POSITION_NED_COV_DATA::EXTRA_CRC,
35058 AUTH_KEY_DATA::ID => AUTH_KEY_DATA::EXTRA_CRC,
35059 HIL_ACTUATOR_CONTROLS_DATA::ID => HIL_ACTUATOR_CONTROLS_DATA::EXTRA_CRC,
35060 COLLISION_DATA::ID => COLLISION_DATA::EXTRA_CRC,
35061 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::ID => {
35062 UAVIONIX_ADSB_OUT_CFG_REGISTRATION_DATA::EXTRA_CRC
35063 }
35064 HIL_STATE_QUATERNION_DATA::ID => HIL_STATE_QUATERNION_DATA::EXTRA_CRC,
35065 UAVIONIX_ADSB_OUT_STATUS_DATA::ID => UAVIONIX_ADSB_OUT_STATUS_DATA::EXTRA_CRC,
35066 MISSION_ACK_DATA::ID => MISSION_ACK_DATA::EXTRA_CRC,
35067 WHEEL_DISTANCE_DATA::ID => WHEEL_DISTANCE_DATA::EXTRA_CRC,
35068 OPTICAL_FLOW_RAD_DATA::ID => OPTICAL_FLOW_RAD_DATA::EXTRA_CRC,
35069 CAMERA_TRACKING_GEO_STATUS_DATA::ID => CAMERA_TRACKING_GEO_STATUS_DATA::EXTRA_CRC,
35070 CELLULAR_CONFIG_DATA::ID => CELLULAR_CONFIG_DATA::EXTRA_CRC,
35071 DATA_STREAM_DATA::ID => DATA_STREAM_DATA::EXTRA_CRC,
35072 PARAM_SET_DATA::ID => PARAM_SET_DATA::EXTRA_CRC,
35073 UAVCAN_NODE_STATUS_DATA::ID => UAVCAN_NODE_STATUS_DATA::EXTRA_CRC,
35074 STORAGE_INFORMATION_DATA::ID => STORAGE_INFORMATION_DATA::EXTRA_CRC,
35075 MISSION_REQUEST_INT_DATA::ID => MISSION_REQUEST_INT_DATA::EXTRA_CRC,
35076 SCALED_PRESSURE_DATA::ID => SCALED_PRESSURE_DATA::EXTRA_CRC,
35077 ENCAPSULATED_DATA_DATA::ID => ENCAPSULATED_DATA_DATA::EXTRA_CRC,
35078 PLAY_TUNE_DATA::ID => PLAY_TUNE_DATA::EXTRA_CRC,
35079 CANFD_FRAME_DATA::ID => CANFD_FRAME_DATA::EXTRA_CRC,
35080 AVAILABLE_MODES_MONITOR_DATA::ID => AVAILABLE_MODES_MONITOR_DATA::EXTRA_CRC,
35081 DEBUG_DATA::ID => DEBUG_DATA::EXTRA_CRC,
35082 CAN_FRAME_DATA::ID => CAN_FRAME_DATA::EXTRA_CRC,
35083 MANUAL_SETPOINT_DATA::ID => MANUAL_SETPOINT_DATA::EXTRA_CRC,
35084 MISSION_SET_CURRENT_DATA::ID => MISSION_SET_CURRENT_DATA::EXTRA_CRC,
35085 BUTTON_CHANGE_DATA::ID => BUTTON_CHANGE_DATA::EXTRA_CRC,
35086 CAN_FILTER_MODIFY_DATA::ID => CAN_FILTER_MODIFY_DATA::EXTRA_CRC,
35087 LOG_DATA_DATA::ID => LOG_DATA_DATA::EXTRA_CRC,
35088 DEBUG_VECT_DATA::ID => DEBUG_VECT_DATA::EXTRA_CRC,
35089 PLAY_TUNE_V2_DATA::ID => PLAY_TUNE_V2_DATA::EXTRA_CRC,
35090 OPEN_DRONE_ID_SELF_ID_DATA::ID => OPEN_DRONE_ID_SELF_ID_DATA::EXTRA_CRC,
35091 COMMAND_CANCEL_DATA::ID => COMMAND_CANCEL_DATA::EXTRA_CRC,
35092 UAVIONIX_ADSB_OUT_CONTROL_DATA::ID => UAVIONIX_ADSB_OUT_CONTROL_DATA::EXTRA_CRC,
35093 RESPONSE_EVENT_ERROR_DATA::ID => RESPONSE_EVENT_ERROR_DATA::EXTRA_CRC,
35094 HEARTBEAT_DATA::ID => HEARTBEAT_DATA::EXTRA_CRC,
35095 EVENT_DATA::ID => EVENT_DATA::EXTRA_CRC,
35096 DEBUG_FLOAT_ARRAY_DATA::ID => DEBUG_FLOAT_ARRAY_DATA::EXTRA_CRC,
35097 COMMAND_INT_DATA::ID => COMMAND_INT_DATA::EXTRA_CRC,
35098 FILE_TRANSFER_PROTOCOL_DATA::ID => FILE_TRANSFER_PROTOCOL_DATA::EXTRA_CRC,
35099 CELLULAR_STATUS_DATA::ID => CELLULAR_STATUS_DATA::EXTRA_CRC,
35100 REQUEST_DATA_STREAM_DATA::ID => REQUEST_DATA_STREAM_DATA::EXTRA_CRC,
35101 PARAM_EXT_REQUEST_LIST_DATA::ID => PARAM_EXT_REQUEST_LIST_DATA::EXTRA_CRC,
35102 WIND_COV_DATA::ID => WIND_COV_DATA::EXTRA_CRC,
35103 ATTITUDE_DATA::ID => ATTITUDE_DATA::EXTRA_CRC,
35104 RADIO_STATUS_DATA::ID => RADIO_STATUS_DATA::EXTRA_CRC,
35105 NAMED_VALUE_FLOAT_DATA::ID => NAMED_VALUE_FLOAT_DATA::EXTRA_CRC,
35106 GPS_GLOBAL_ORIGIN_DATA::ID => GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
35107 POSITION_TARGET_GLOBAL_INT_DATA::ID => POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC,
35108 GPS_STATUS_DATA::ID => GPS_STATUS_DATA::EXTRA_CRC,
35109 PARAM_REQUEST_LIST_DATA::ID => PARAM_REQUEST_LIST_DATA::EXTRA_CRC,
35110 OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::ID => OPEN_DRONE_ID_SYSTEM_UPDATE_DATA::EXTRA_CRC,
35111 FUEL_STATUS_DATA::ID => FUEL_STATUS_DATA::EXTRA_CRC,
35112 MEMORY_VECT_DATA::ID => MEMORY_VECT_DATA::EXTRA_CRC,
35113 UAVIONIX_ADSB_OUT_DYNAMIC_DATA::ID => UAVIONIX_ADSB_OUT_DYNAMIC_DATA::EXTRA_CRC,
35114 CAMERA_SETTINGS_DATA::ID => CAMERA_SETTINGS_DATA::EXTRA_CRC,
35115 SERVO_OUTPUT_RAW_DATA::ID => SERVO_OUTPUT_RAW_DATA::EXTRA_CRC,
35116 ACTUATOR_CONTROL_TARGET_DATA::ID => ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
35117 ATTITUDE_TARGET_DATA::ID => ATTITUDE_TARGET_DATA::EXTRA_CRC,
35118 SCALED_IMU_DATA::ID => SCALED_IMU_DATA::EXTRA_CRC,
35119 STATUSTEXT_DATA::ID => STATUSTEXT_DATA::EXTRA_CRC,
35120 ALTITUDE_DATA::ID => ALTITUDE_DATA::EXTRA_CRC,
35121 CHANGE_OPERATOR_CONTROL_DATA::ID => CHANGE_OPERATOR_CONTROL_DATA::EXTRA_CRC,
35122 RAW_RPM_DATA::ID => RAW_RPM_DATA::EXTRA_CRC,
35123 GPS2_RTK_DATA::ID => GPS2_RTK_DATA::EXTRA_CRC,
35124 OPTICAL_FLOW_DATA::ID => OPTICAL_FLOW_DATA::EXTRA_CRC,
35125 TERRAIN_DATA_DATA::ID => TERRAIN_DATA_DATA::EXTRA_CRC,
35126 ORBIT_EXECUTION_STATUS_DATA::ID => ORBIT_EXECUTION_STATUS_DATA::EXTRA_CRC,
35127 GLOBAL_POSITION_INT_DATA::ID => GLOBAL_POSITION_INT_DATA::EXTRA_CRC,
35128 TERRAIN_REPORT_DATA::ID => TERRAIN_REPORT_DATA::EXTRA_CRC,
35129 SAFETY_SET_ALLOWED_AREA_DATA::ID => SAFETY_SET_ALLOWED_AREA_DATA::EXTRA_CRC,
35130 SET_HOME_POSITION_DATA::ID => SET_HOME_POSITION_DATA::EXTRA_CRC,
35131 AUTOPILOT_VERSION_DATA::ID => AUTOPILOT_VERSION_DATA::EXTRA_CRC,
35132 SETUP_SIGNING_DATA::ID => SETUP_SIGNING_DATA::EXTRA_CRC,
35133 ILLUMINATOR_STATUS_DATA::ID => ILLUMINATOR_STATUS_DATA::EXTRA_CRC,
35134 UAVCAN_NODE_INFO_DATA::ID => UAVCAN_NODE_INFO_DATA::EXTRA_CRC,
35135 GIMBAL_DEVICE_INFORMATION_DATA::ID => GIMBAL_DEVICE_INFORMATION_DATA::EXTRA_CRC,
35136 GIMBAL_MANAGER_SET_ATTITUDE_DATA::ID => GIMBAL_MANAGER_SET_ATTITUDE_DATA::EXTRA_CRC,
35137 LOGGING_DATA_ACKED_DATA::ID => LOGGING_DATA_ACKED_DATA::EXTRA_CRC,
35138 RC_CHANNELS_RAW_DATA::ID => RC_CHANNELS_RAW_DATA::EXTRA_CRC,
35139 LINK_NODE_STATUS_DATA::ID => LINK_NODE_STATUS_DATA::EXTRA_CRC,
35140 MISSION_ITEM_REACHED_DATA::ID => MISSION_ITEM_REACHED_DATA::EXTRA_CRC,
35141 SET_POSITION_TARGET_GLOBAL_INT_DATA::ID => {
35142 SET_POSITION_TARGET_GLOBAL_INT_DATA::EXTRA_CRC
35143 }
35144 SMART_BATTERY_INFO_DATA::ID => SMART_BATTERY_INFO_DATA::EXTRA_CRC,
35145 SET_GPS_GLOBAL_ORIGIN_DATA::ID => SET_GPS_GLOBAL_ORIGIN_DATA::EXTRA_CRC,
35146 VIBRATION_DATA::ID => VIBRATION_DATA::EXTRA_CRC,
35147 GIMBAL_MANAGER_STATUS_DATA::ID => GIMBAL_MANAGER_STATUS_DATA::EXTRA_CRC,
35148 MISSION_ITEM_INT_DATA::ID => MISSION_ITEM_INT_DATA::EXTRA_CRC,
35149 POWER_STATUS_DATA::ID => POWER_STATUS_DATA::EXTRA_CRC,
35150 LOGGING_DATA_DATA::ID => LOGGING_DATA_DATA::EXTRA_CRC,
35151 CHANGE_OPERATOR_CONTROL_ACK_DATA::ID => CHANGE_OPERATOR_CONTROL_ACK_DATA::EXTRA_CRC,
35152 GPS_RTK_DATA::ID => GPS_RTK_DATA::EXTRA_CRC,
35153 FLIGHT_INFORMATION_DATA::ID => FLIGHT_INFORMATION_DATA::EXTRA_CRC,
35154 SUPPORTED_TUNES_DATA::ID => SUPPORTED_TUNES_DATA::EXTRA_CRC,
35155 WIFI_CONFIG_AP_DATA::ID => WIFI_CONFIG_AP_DATA::EXTRA_CRC,
35156 TERRAIN_CHECK_DATA::ID => TERRAIN_CHECK_DATA::EXTRA_CRC,
35157 RAW_PRESSURE_DATA::ID => RAW_PRESSURE_DATA::EXTRA_CRC,
35158 OPEN_DRONE_ID_AUTHENTICATION_DATA::ID => OPEN_DRONE_ID_AUTHENTICATION_DATA::EXTRA_CRC,
35159 ESC_INFO_DATA::ID => ESC_INFO_DATA::EXTRA_CRC,
35160 DISTANCE_SENSOR_DATA::ID => DISTANCE_SENSOR_DATA::EXTRA_CRC,
35161 HIL_RC_INPUTS_RAW_DATA::ID => HIL_RC_INPUTS_RAW_DATA::EXTRA_CRC,
35162 ISBD_LINK_STATUS_DATA::ID => ISBD_LINK_STATUS_DATA::EXTRA_CRC,
35163 RC_CHANNELS_SCALED_DATA::ID => RC_CHANNELS_SCALED_DATA::EXTRA_CRC,
35164 SCALED_IMU2_DATA::ID => SCALED_IMU2_DATA::EXTRA_CRC,
35165 HIL_SENSOR_DATA::ID => HIL_SENSOR_DATA::EXTRA_CRC,
35166 RESOURCE_REQUEST_DATA::ID => RESOURCE_REQUEST_DATA::EXTRA_CRC,
35167 CAMERA_THERMAL_RANGE_DATA::ID => CAMERA_THERMAL_RANGE_DATA::EXTRA_CRC,
35168 TIMESYNC_DATA::ID => TIMESYNC_DATA::EXTRA_CRC,
35169 OPEN_DRONE_ID_MESSAGE_PACK_DATA::ID => OPEN_DRONE_ID_MESSAGE_PACK_DATA::EXTRA_CRC,
35170 LOG_REQUEST_DATA_DATA::ID => LOG_REQUEST_DATA_DATA::EXTRA_CRC,
35171 COMPONENT_METADATA_DATA::ID => COMPONENT_METADATA_DATA::EXTRA_CRC,
35172 MAG_CAL_REPORT_DATA::ID => MAG_CAL_REPORT_DATA::EXTRA_CRC,
35173 NAMED_VALUE_INT_DATA::ID => NAMED_VALUE_INT_DATA::EXTRA_CRC,
35174 SAFETY_ALLOWED_AREA_DATA::ID => SAFETY_ALLOWED_AREA_DATA::EXTRA_CRC,
35175 GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::ID => GIMBAL_DEVICE_ATTITUDE_STATUS_DATA::EXTRA_CRC,
35176 ESC_STATUS_DATA::ID => ESC_STATUS_DATA::EXTRA_CRC,
35177 PARAM_EXT_REQUEST_READ_DATA::ID => PARAM_EXT_REQUEST_READ_DATA::EXTRA_CRC,
35178 SCALED_IMU3_DATA::ID => SCALED_IMU3_DATA::EXTRA_CRC,
35179 ESTIMATOR_STATUS_DATA::ID => ESTIMATOR_STATUS_DATA::EXTRA_CRC,
35180 PARAM_EXT_ACK_DATA::ID => PARAM_EXT_ACK_DATA::EXTRA_CRC,
35181 V2_EXTENSION_DATA::ID => V2_EXTENSION_DATA::EXTRA_CRC,
35182 SET_ACTUATOR_CONTROL_TARGET_DATA::ID => SET_ACTUATOR_CONTROL_TARGET_DATA::EXTRA_CRC,
35183 RC_CHANNELS_OVERRIDE_DATA::ID => RC_CHANNELS_OVERRIDE_DATA::EXTRA_CRC,
35184 DATA_TRANSMISSION_HANDSHAKE_DATA::ID => DATA_TRANSMISSION_HANDSHAKE_DATA::EXTRA_CRC,
35185 LOCAL_POSITION_NED_DATA::ID => LOCAL_POSITION_NED_DATA::EXTRA_CRC,
35186 EXTENDED_SYS_STATE_DATA::ID => EXTENDED_SYS_STATE_DATA::EXTRA_CRC,
35187 FENCE_STATUS_DATA::ID => FENCE_STATUS_DATA::EXTRA_CRC,
35188 ONBOARD_COMPUTER_STATUS_DATA::ID => ONBOARD_COMPUTER_STATUS_DATA::EXTRA_CRC,
35189 MISSION_REQUEST_LIST_DATA::ID => MISSION_REQUEST_LIST_DATA::EXTRA_CRC,
35190 MESSAGE_INTERVAL_DATA::ID => MESSAGE_INTERVAL_DATA::EXTRA_CRC,
35191 TERRAIN_REQUEST_DATA::ID => TERRAIN_REQUEST_DATA::EXTRA_CRC,
35192 SCALED_PRESSURE3_DATA::ID => SCALED_PRESSURE3_DATA::EXTRA_CRC,
35193 REQUEST_EVENT_DATA::ID => REQUEST_EVENT_DATA::EXTRA_CRC,
35194 SET_ATTITUDE_TARGET_DATA::ID => SET_ATTITUDE_TARGET_DATA::EXTRA_CRC,
35195 SET_POSITION_TARGET_LOCAL_NED_DATA::ID => SET_POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
35196 LOGGING_ACK_DATA::ID => LOGGING_ACK_DATA::EXTRA_CRC,
35197 LOG_ERASE_DATA::ID => LOG_ERASE_DATA::EXTRA_CRC,
35198 OPEN_DRONE_ID_LOCATION_DATA::ID => OPEN_DRONE_ID_LOCATION_DATA::EXTRA_CRC,
35199 UAVIONIX_ADSB_OUT_CFG_DATA::ID => UAVIONIX_ADSB_OUT_CFG_DATA::EXTRA_CRC,
35200 TRAJECTORY_REPRESENTATION_BEZIER_DATA::ID => {
35201 TRAJECTORY_REPRESENTATION_BEZIER_DATA::EXTRA_CRC
35202 }
35203 SIM_STATE_DATA::ID => SIM_STATE_DATA::EXTRA_CRC,
35204 ODOMETRY_DATA::ID => ODOMETRY_DATA::EXTRA_CRC,
35205 VISION_POSITION_ESTIMATE_DATA::ID => VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC,
35206 PARAM_REQUEST_READ_DATA::ID => PARAM_REQUEST_READ_DATA::EXTRA_CRC,
35207 BATTERY_INFO_DATA::ID => BATTERY_INFO_DATA::EXTRA_CRC,
35208 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::ID => {
35209 LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_DATA::EXTRA_CRC
35210 }
35211 VIDEO_STREAM_STATUS_DATA::ID => VIDEO_STREAM_STATUS_DATA::EXTRA_CRC,
35212 ATT_POS_MOCAP_DATA::ID => ATT_POS_MOCAP_DATA::EXTRA_CRC,
35213 UAVIONIX_ADSB_GET_DATA::ID => UAVIONIX_ADSB_GET_DATA::EXTRA_CRC,
35214 MISSION_ITEM_DATA::ID => MISSION_ITEM_DATA::EXTRA_CRC,
35215 VISION_SPEED_ESTIMATE_DATA::ID => VISION_SPEED_ESTIMATE_DATA::EXTRA_CRC,
35216 MISSION_WRITE_PARTIAL_LIST_DATA::ID => MISSION_WRITE_PARTIAL_LIST_DATA::EXTRA_CRC,
35217 VFR_HUD_DATA::ID => VFR_HUD_DATA::EXTRA_CRC,
35218 POSITION_TARGET_LOCAL_NED_DATA::ID => POSITION_TARGET_LOCAL_NED_DATA::EXTRA_CRC,
35219 MISSION_CLEAR_ALL_DATA::ID => MISSION_CLEAR_ALL_DATA::EXTRA_CRC,
35220 MANUAL_CONTROL_DATA::ID => MANUAL_CONTROL_DATA::EXTRA_CRC,
35221 AVAILABLE_MODES_DATA::ID => AVAILABLE_MODES_DATA::EXTRA_CRC,
35222 TIME_ESTIMATE_TO_TARGET_DATA::ID => TIME_ESTIMATE_TO_TARGET_DATA::EXTRA_CRC,
35223 GPS_RAW_INT_DATA::ID => GPS_RAW_INT_DATA::EXTRA_CRC,
35224 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::ID => {
35225 UAVIONIX_ADSB_TRANSCEIVER_HEALTH_REPORT_DATA::EXTRA_CRC
35226 }
35227 VICON_POSITION_ESTIMATE_DATA::ID => VICON_POSITION_ESTIMATE_DATA::EXTRA_CRC,
35228 SCALED_PRESSURE2_DATA::ID => SCALED_PRESSURE2_DATA::EXTRA_CRC,
35229 CONTROL_SYSTEM_STATE_DATA::ID => CONTROL_SYSTEM_STATE_DATA::EXTRA_CRC,
35230 MISSION_REQUEST_PARTIAL_LIST_DATA::ID => MISSION_REQUEST_PARTIAL_LIST_DATA::EXTRA_CRC,
35231 HOME_POSITION_DATA::ID => HOME_POSITION_DATA::EXTRA_CRC,
35232 CAMERA_TRACKING_IMAGE_STATUS_DATA::ID => CAMERA_TRACKING_IMAGE_STATUS_DATA::EXTRA_CRC,
35233 ACTUATOR_OUTPUT_STATUS_DATA::ID => ACTUATOR_OUTPUT_STATUS_DATA::EXTRA_CRC,
35234 LOG_REQUEST_END_DATA::ID => LOG_REQUEST_END_DATA::EXTRA_CRC,
35235 RC_CHANNELS_DATA::ID => RC_CHANNELS_DATA::EXTRA_CRC,
35236 ATTITUDE_QUATERNION_COV_DATA::ID => ATTITUDE_QUATERNION_COV_DATA::EXTRA_CRC,
35237 CAMERA_TRIGGER_DATA::ID => CAMERA_TRIGGER_DATA::EXTRA_CRC,
35238 FOLLOW_TARGET_DATA::ID => FOLLOW_TARGET_DATA::EXTRA_CRC,
35239 GLOBAL_POSITION_INT_COV_DATA::ID => GLOBAL_POSITION_INT_COV_DATA::EXTRA_CRC,
35240 MOUNT_ORIENTATION_DATA::ID => MOUNT_ORIENTATION_DATA::EXTRA_CRC,
35241 GENERATOR_STATUS_DATA::ID => GENERATOR_STATUS_DATA::EXTRA_CRC,
35242 GPS_RTCM_DATA_DATA::ID => GPS_RTCM_DATA_DATA::EXTRA_CRC,
35243 NAV_CONTROLLER_OUTPUT_DATA::ID => NAV_CONTROLLER_OUTPUT_DATA::EXTRA_CRC,
35244 GLOBAL_VISION_POSITION_ESTIMATE_DATA::ID => {
35245 GLOBAL_VISION_POSITION_ESTIMATE_DATA::EXTRA_CRC
35246 }
35247 PARAM_EXT_VALUE_DATA::ID => PARAM_EXT_VALUE_DATA::EXTRA_CRC,
35248 CAMERA_CAPTURE_STATUS_DATA::ID => CAMERA_CAPTURE_STATUS_DATA::EXTRA_CRC,
35249 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::ID => {
35250 GIMBAL_MANAGER_SET_MANUAL_CONTROL_DATA::EXTRA_CRC
35251 }
35252 GIMBAL_MANAGER_INFORMATION_DATA::ID => GIMBAL_MANAGER_INFORMATION_DATA::EXTRA_CRC,
35253 HIGH_LATENCY2_DATA::ID => HIGH_LATENCY2_DATA::EXTRA_CRC,
35254 HIGHRES_IMU_DATA::ID => HIGHRES_IMU_DATA::EXTRA_CRC,
35255 HIL_CONTROLS_DATA::ID => HIL_CONTROLS_DATA::EXTRA_CRC,
35256 MISSION_REQUEST_DATA::ID => MISSION_REQUEST_DATA::EXTRA_CRC,
35257 LANDING_TARGET_DATA::ID => LANDING_TARGET_DATA::EXTRA_CRC,
35258 LOG_REQUEST_LIST_DATA::ID => LOG_REQUEST_LIST_DATA::EXTRA_CRC,
35259 CAMERA_FOV_STATUS_DATA::ID => CAMERA_FOV_STATUS_DATA::EXTRA_CRC,
35260 LOG_ENTRY_DATA::ID => LOG_ENTRY_DATA::EXTRA_CRC,
35261 GPS_INJECT_DATA_DATA::ID => GPS_INJECT_DATA_DATA::EXTRA_CRC,
35262 PARAM_VALUE_DATA::ID => PARAM_VALUE_DATA::EXTRA_CRC,
35263 GIMBAL_MANAGER_SET_PITCHYAW_DATA::ID => GIMBAL_MANAGER_SET_PITCHYAW_DATA::EXTRA_CRC,
35264 CURRENT_EVENT_SEQUENCE_DATA::ID => CURRENT_EVENT_SEQUENCE_DATA::EXTRA_CRC,
35265 CAMERA_INFORMATION_DATA::ID => CAMERA_INFORMATION_DATA::EXTRA_CRC,
35266 OPEN_DRONE_ID_OPERATOR_ID_DATA::ID => OPEN_DRONE_ID_OPERATOR_ID_DATA::EXTRA_CRC,
35267 COMPONENT_INFORMATION_DATA::ID => COMPONENT_INFORMATION_DATA::EXTRA_CRC,
35268 COMMAND_LONG_DATA::ID => COMMAND_LONG_DATA::EXTRA_CRC,
35269 PARAM_EXT_SET_DATA::ID => PARAM_EXT_SET_DATA::EXTRA_CRC,
35270 GPS_INPUT_DATA::ID => GPS_INPUT_DATA::EXTRA_CRC,
35271 SET_MODE_DATA::ID => SET_MODE_DATA::EXTRA_CRC,
35272 AIS_VESSEL_DATA::ID => AIS_VESSEL_DATA::EXTRA_CRC,
35273 ATTITUDE_QUATERNION_DATA::ID => ATTITUDE_QUATERNION_DATA::EXTRA_CRC,
35274 CURRENT_MODE_DATA::ID => CURRENT_MODE_DATA::EXTRA_CRC,
35275 GIMBAL_DEVICE_SET_ATTITUDE_DATA::ID => GIMBAL_DEVICE_SET_ATTITUDE_DATA::EXTRA_CRC,
35276 HYGROMETER_SENSOR_DATA::ID => HYGROMETER_SENSOR_DATA::EXTRA_CRC,
35277 PARAM_MAP_RC_DATA::ID => PARAM_MAP_RC_DATA::EXTRA_CRC,
35278 COMPONENT_INFORMATION_BASIC_DATA::ID => COMPONENT_INFORMATION_BASIC_DATA::EXTRA_CRC,
35279 OPEN_DRONE_ID_SYSTEM_DATA::ID => OPEN_DRONE_ID_SYSTEM_DATA::EXTRA_CRC,
35280 COMMAND_ACK_DATA::ID => COMMAND_ACK_DATA::EXTRA_CRC,
35281 SERIAL_CONTROL_DATA::ID => SERIAL_CONTROL_DATA::EXTRA_CRC,
35282 _ => 0,
35283 }
35284 }
35285 fn target_system_id(&self) -> Option<u8> {
35286 match self {
35287 Self::MISSION_COUNT(inner) => Some(inner.target_system),
35288 Self::TUNNEL(inner) => Some(inner.target_system),
35289 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_system),
35290 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_system),
35291 Self::PING(inner) => Some(inner.target_system),
35292 Self::MISSION_ACK(inner) => Some(inner.target_system),
35293 Self::PARAM_SET(inner) => Some(inner.target_system),
35294 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_system),
35295 Self::PLAY_TUNE(inner) => Some(inner.target_system),
35296 Self::CANFD_FRAME(inner) => Some(inner.target_system),
35297 Self::CAN_FRAME(inner) => Some(inner.target_system),
35298 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_system),
35299 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_system),
35300 Self::PLAY_TUNE_V2(inner) => Some(inner.target_system),
35301 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_system),
35302 Self::COMMAND_CANCEL(inner) => Some(inner.target_system),
35303 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_system),
35304 Self::COMMAND_INT(inner) => Some(inner.target_system),
35305 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_system),
35306 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_system),
35307 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_system),
35308 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_system),
35309 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_system),
35310 Self::CHANGE_OPERATOR_CONTROL(inner) => Some(inner.target_system),
35311 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_system),
35312 Self::SET_HOME_POSITION(inner) => Some(inner.target_system),
35313 Self::SETUP_SIGNING(inner) => Some(inner.target_system),
35314 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_system),
35315 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_system),
35316 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_system),
35317 Self::SET_GPS_GLOBAL_ORIGIN(inner) => Some(inner.target_system),
35318 Self::MISSION_ITEM_INT(inner) => Some(inner.target_system),
35319 Self::LOGGING_DATA(inner) => Some(inner.target_system),
35320 Self::SUPPORTED_TUNES(inner) => Some(inner.target_system),
35321 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_system),
35322 Self::TIMESYNC(inner) => Some(inner.target_system),
35323 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_system),
35324 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_system),
35325 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_system),
35326 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_system),
35327 Self::V2_EXTENSION(inner) => Some(inner.target_system),
35328 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_system),
35329 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_system),
35330 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_system),
35331 Self::REQUEST_EVENT(inner) => Some(inner.target_system),
35332 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_system),
35333 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_system),
35334 Self::LOGGING_ACK(inner) => Some(inner.target_system),
35335 Self::LOG_ERASE(inner) => Some(inner.target_system),
35336 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_system),
35337 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_system),
35338 Self::MISSION_ITEM(inner) => Some(inner.target_system),
35339 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_system),
35340 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_system),
35341 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_system),
35342 Self::LOG_REQUEST_END(inner) => Some(inner.target_system),
35343 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_system),
35344 Self::MISSION_REQUEST(inner) => Some(inner.target_system),
35345 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_system),
35346 Self::GPS_INJECT_DATA(inner) => Some(inner.target_system),
35347 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_system),
35348 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_system),
35349 Self::COMMAND_LONG(inner) => Some(inner.target_system),
35350 Self::PARAM_EXT_SET(inner) => Some(inner.target_system),
35351 Self::SET_MODE(inner) => Some(inner.target_system),
35352 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_system),
35353 Self::PARAM_MAP_RC(inner) => Some(inner.target_system),
35354 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_system),
35355 Self::COMMAND_ACK(inner) => Some(inner.target_system),
35356 Self::SERIAL_CONTROL(inner) => Some(inner.target_system),
35357 _ => None,
35358 }
35359 }
35360 fn target_component_id(&self) -> Option<u8> {
35361 match self {
35362 Self::MISSION_COUNT(inner) => Some(inner.target_component),
35363 Self::TUNNEL(inner) => Some(inner.target_component),
35364 Self::AUTOPILOT_STATE_FOR_GIMBAL_DEVICE(inner) => Some(inner.target_component),
35365 Self::OPEN_DRONE_ID_BASIC_ID(inner) => Some(inner.target_component),
35366 Self::PING(inner) => Some(inner.target_component),
35367 Self::MISSION_ACK(inner) => Some(inner.target_component),
35368 Self::PARAM_SET(inner) => Some(inner.target_component),
35369 Self::MISSION_REQUEST_INT(inner) => Some(inner.target_component),
35370 Self::PLAY_TUNE(inner) => Some(inner.target_component),
35371 Self::CANFD_FRAME(inner) => Some(inner.target_component),
35372 Self::CAN_FRAME(inner) => Some(inner.target_component),
35373 Self::MISSION_SET_CURRENT(inner) => Some(inner.target_component),
35374 Self::CAN_FILTER_MODIFY(inner) => Some(inner.target_component),
35375 Self::PLAY_TUNE_V2(inner) => Some(inner.target_component),
35376 Self::OPEN_DRONE_ID_SELF_ID(inner) => Some(inner.target_component),
35377 Self::COMMAND_CANCEL(inner) => Some(inner.target_component),
35378 Self::RESPONSE_EVENT_ERROR(inner) => Some(inner.target_component),
35379 Self::COMMAND_INT(inner) => Some(inner.target_component),
35380 Self::FILE_TRANSFER_PROTOCOL(inner) => Some(inner.target_component),
35381 Self::REQUEST_DATA_STREAM(inner) => Some(inner.target_component),
35382 Self::PARAM_EXT_REQUEST_LIST(inner) => Some(inner.target_component),
35383 Self::PARAM_REQUEST_LIST(inner) => Some(inner.target_component),
35384 Self::OPEN_DRONE_ID_SYSTEM_UPDATE(inner) => Some(inner.target_component),
35385 Self::SAFETY_SET_ALLOWED_AREA(inner) => Some(inner.target_component),
35386 Self::SETUP_SIGNING(inner) => Some(inner.target_component),
35387 Self::GIMBAL_MANAGER_SET_ATTITUDE(inner) => Some(inner.target_component),
35388 Self::LOGGING_DATA_ACKED(inner) => Some(inner.target_component),
35389 Self::SET_POSITION_TARGET_GLOBAL_INT(inner) => Some(inner.target_component),
35390 Self::MISSION_ITEM_INT(inner) => Some(inner.target_component),
35391 Self::LOGGING_DATA(inner) => Some(inner.target_component),
35392 Self::SUPPORTED_TUNES(inner) => Some(inner.target_component),
35393 Self::OPEN_DRONE_ID_AUTHENTICATION(inner) => Some(inner.target_component),
35394 Self::TIMESYNC(inner) => Some(inner.target_component),
35395 Self::OPEN_DRONE_ID_MESSAGE_PACK(inner) => Some(inner.target_component),
35396 Self::LOG_REQUEST_DATA(inner) => Some(inner.target_component),
35397 Self::GIMBAL_DEVICE_ATTITUDE_STATUS(inner) => Some(inner.target_component),
35398 Self::PARAM_EXT_REQUEST_READ(inner) => Some(inner.target_component),
35399 Self::V2_EXTENSION(inner) => Some(inner.target_component),
35400 Self::SET_ACTUATOR_CONTROL_TARGET(inner) => Some(inner.target_component),
35401 Self::RC_CHANNELS_OVERRIDE(inner) => Some(inner.target_component),
35402 Self::MISSION_REQUEST_LIST(inner) => Some(inner.target_component),
35403 Self::REQUEST_EVENT(inner) => Some(inner.target_component),
35404 Self::SET_ATTITUDE_TARGET(inner) => Some(inner.target_component),
35405 Self::SET_POSITION_TARGET_LOCAL_NED(inner) => Some(inner.target_component),
35406 Self::LOGGING_ACK(inner) => Some(inner.target_component),
35407 Self::LOG_ERASE(inner) => Some(inner.target_component),
35408 Self::OPEN_DRONE_ID_LOCATION(inner) => Some(inner.target_component),
35409 Self::PARAM_REQUEST_READ(inner) => Some(inner.target_component),
35410 Self::MISSION_ITEM(inner) => Some(inner.target_component),
35411 Self::MISSION_WRITE_PARTIAL_LIST(inner) => Some(inner.target_component),
35412 Self::MISSION_CLEAR_ALL(inner) => Some(inner.target_component),
35413 Self::MISSION_REQUEST_PARTIAL_LIST(inner) => Some(inner.target_component),
35414 Self::LOG_REQUEST_END(inner) => Some(inner.target_component),
35415 Self::GIMBAL_MANAGER_SET_MANUAL_CONTROL(inner) => Some(inner.target_component),
35416 Self::MISSION_REQUEST(inner) => Some(inner.target_component),
35417 Self::LOG_REQUEST_LIST(inner) => Some(inner.target_component),
35418 Self::GPS_INJECT_DATA(inner) => Some(inner.target_component),
35419 Self::GIMBAL_MANAGER_SET_PITCHYAW(inner) => Some(inner.target_component),
35420 Self::OPEN_DRONE_ID_OPERATOR_ID(inner) => Some(inner.target_component),
35421 Self::COMMAND_LONG(inner) => Some(inner.target_component),
35422 Self::PARAM_EXT_SET(inner) => Some(inner.target_component),
35423 Self::GIMBAL_DEVICE_SET_ATTITUDE(inner) => Some(inner.target_component),
35424 Self::PARAM_MAP_RC(inner) => Some(inner.target_component),
35425 Self::OPEN_DRONE_ID_SYSTEM(inner) => Some(inner.target_component),
35426 Self::COMMAND_ACK(inner) => Some(inner.target_component),
35427 Self::SERIAL_CONTROL(inner) => Some(inner.target_component),
35428 _ => None,
35429 }
35430 }
35431}